# Failure Injection

System failure injection allows you to induce different types of sensor and system failures, either programmatically using the [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html), or "manually" via a PX4 console like the [MAVLink shell](https://px4.gitbook.io/px4-user-guide/development/consoles/mavlink_shell#mavlink-shell). This enables easier testing of [safety failsafe](https://px4.gitbook.io/px4-user-guide/config/safety#safety-configuration-failsafes) behaviour, and more generally, of how PX4 behaves when systems and sensors stop working correctly.

Failure injection is disabled by default, and can be enabled using the [SYS\_FAILURE\_EN](https://px4.gitbook.io/px4-user-guide/advanced_config/parameter_reference#SYS_FAILURE_EN) parameter.

:::warning Failure injection still in development. At time of writing (PX4 v1.12):

* It can only be used in simulation (support for both failure injection in real flight is planned).
* Many failure types are not broadly implemented. In those cases the command will return with an "unsupported" message. :::

## Failure System Command

Failures can be injected using the [failure system command](https://px4.gitbook.io/px4-user-guide/modules_main/modules_command#failure) from any PX4 console/shell, specifying both the target and type of the failure.

### Syntax

The full syntax of the [failure](https://px4.gitbook.io/px4-user-guide/modules_main/modules_command#failure) command is:

```
failure <component> <failure_type> [-i <instance_number>]
```

where:

* *component*:
  * Sensors:
    * `gyro`: Gyro.
    * `accel`: Accelerometer.
    * `mag`: Magnetometer
    * `baro`: Barometer
    * `gps`: GPS
    * `optical_flow`: Optical flow.
    * `vio`: Visual inertial odometry.
    * `distance_sensor`: Distance sensor (rangefinder).
    * `airspeed`: Airspeed sensor.
  * Systems:
    * `battery`: Battery.
    * `motor`: Motor.
    * `servo`: Servo.
    * `avoidance`: Avoidance.
    * `rc_signal`: RC Signal.
    * `mavlink_signal`: MAVLink signal (data telemetry).
* *failure\_type*:
  * `ok`: Publish as normal (Disable failure injection).
  * `off`: Stop publishing.
  * `stuck`: Report same value every time (*could* indicate a malfunctioning sensor).
  * `garbage`: Publish random noise. This looks like reading uninitialized memory.
  * `wrong`: Publish invalid values (that still look reasonable/aren't "garbage").
  * `slow`: Publish at a reduced rate.
  * `delayed`: Publish valid data with a significant delay.
  * `intermittent`: Publish intermittently.
* *instance number* (optional): Instance number of affected sensor. 0 (default) indicates all sensors of specified type.

### Example

To simulate losing RC signal without having to turn off your RC controller:

1. Enable the parameter [SYS\_FAILURE\_EN](https://px4.gitbook.io/px4-user-guide/advanced_config/parameter_reference#SYS_FAILURE_EN).
2. Enter the following commands on the MAVLink console or SITL *pxh shell*:

   ```bash
   # Fail RC (turn publishing off)
   failure rc_signal off

   # Restart RC publishing
   failure rc_signal ok
   ```

## MAVSDK Failure Plugin

The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. It is used in [PX4 Integration Testing](https://px4.gitbook.io/px4-user-guide/development/test_and_ci/integration_testing_mavsdk) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk\_tests/autopilot\_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)).

The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection.
