Skip to content

Commit

Permalink
PX4 v1.13 MAVLink parachute support (#1943)
Browse files Browse the repository at this point in the history
  • Loading branch information
hamishwillee authored Jul 27, 2022
1 parent 7992c83 commit 883ad47
Show file tree
Hide file tree
Showing 2 changed files with 63 additions and 30 deletions.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
93 changes: 63 additions & 30 deletions en/peripherals/parachute.md
Original file line number Diff line number Diff line change
@@ -1,18 +1,20 @@
# Parachute

PX4 can be configured to trigger a parachute connected to a free PWM output during [flight termination](../advanced_config/flight_termination.md).
PX4 can be configured to trigger a parachute during [flight termination](../advanced_config/flight_termination.md).

This topic provides the specific example of how to set up a parachute, using a spring-loaded launcher from [Fruity Chutes](https://fruitychutes.com/buyachute/drone-and-uav-parachute-recovery-c-21/harrier-drone-parachute-launcher-c-21_33/).
The parachute can be connected to a free PWM output or via [MAVLink](#mavlink-parachutes).

:::note
PX4 does not know that it is launching a parachute; during flight termination it just turns off all controllers and sets all PWM outputs to their failsafe values.
You can therefore use this feature to activate multiple complementary safety devices connected to different outputs.
During flight termination PX4 turns off all controllers and sets all PWM outputs to their failsafe values (including those connected to PWM outputs) and triggers any connected MAVLink parachutes.

You can therefore use this feature to activate multiple complementary safety devices connected to different outputs.
For more information see [Flight Termination Configuration](../advanced_config/flight_termination.md).
:::

## Using Parachutes

Below are a few considerations when using parachutes:

- A parachute does not guarantee that the vehicle will not be destroyed or cause harm!
You must always fly with safety in mind.
- Parachutes require careful usage to be effective.
Expand All @@ -27,50 +29,81 @@ Below are a few considerations when using parachutes:
## Parachute Setup

Flight termination (and hence parachute deployment) may be triggered by safety checks such as RC Loss, geofence violation, and so on, from attitude triggers and other failure detector checks, or by a command from a ground station.
During flight termination PX4 sets PWM outputs to their "failsafe" values (failsafe values turn off motors, but may be used to turn on/trigger the parachute.
During flight termination PX4 sets PWM outputs to their "failsafe" values (failsafe values turn off motors, but may be used to turn on/trigger the parachute).
If a MAVLink parachute is connected and healthy, a command will be sent to activate it.

Parachute setup therefore involves:
- Connecting the parachute to unused outputs and setting their failsafe values to levels that will trigger the parachute (using appropriate parameters).
- Configuring [flight termination](../advanced_config/flight_termination.md) as the appropriate action for those safety and failure cases where the parachute should be deployed.

The setup below explains how you might configure a quad multicopter with motors on MAIN 1-4 and a parachute on MAIN PWM port 7.
The PWM values mentioned are for the *Fruity Chutes* parachute we tested.
- Configuring [flight termination](../advanced_config/flight_termination.md) as the appropriate action for those safety and failure cases where the parachute should be deployed.
- Configure PX4 to deploy the parachute during flight termination (set PWM output levels appropriately or send the MAVLink parachute deploy command).
- Configure PX4 output levels to disable motors on failsafe.
This is the default so usually nothing is required (for servos it's the center value).

### Enable Flight Termination

:::tip
For the first test, try on the bench, without the props and with an unloaded parachute device!
To enable flight termination:
- Set [Safety](../config/safety.md) action to *Flight termination* for checks where you want the parachute to trigger.
- Set [Failure Detector](../config/safety.md#failure-detector) pitch angles, roll angles and time triggers for crash/flip detection, and disable the failure/IMU timeout circuit breaker (i.e. set [CBRK_FLIGHTTERM=0](../advanced_config/parameter_reference.md#CBRK_FLIGHTTERM)).

:::note
You can also configure an [external Automatic Trigger System (ATS)](../config/safety.md#external-automatic-trigger-system-ats) for failure detection.
:::

Hardware setup:
- Connect the parachute to the IO port (MAIN), channel 7 (starting from 1).
- Power the servo rail - i.e. connect a 5V BEC to the servo rail.
### Parachute Output Bus Setup

Enable flight termination:
- Set [Safety](../config/safety.md) action to *Flight termination* for checks where you want the parachute to trigger
- Set [Failure Detector](../config/safety.md#failure-detector) pitch angles, roll angles and time triggers for crash/flip detection, and disable the failure/IMU timeout circuit breaker (i.e. set [CBRK_FLIGHTTERM=0](../advanced_config/parameter_reference.md#CBRK_FLIGHTTERM)).

:::note
You can also configure an [external ATS](../config/safety.md#external-automatic-trigger-system-ats) for failure detection.
:::
If the parachute is triggered by a PWM or CAN output then it must first be connected to an unused output (for the purpose of this example, below we assume AUX PWM output 6 is used).
You will probably also need to separately power the parachute servo.
This is might be done by connecting a 5V BEC to the Flight Controller servo rail, and powering the parachute from it.

Parachute settings
- Set [PWM_MAIN_DIS7](../advanced_config/parameter_reference.md#PWM_MAIN_DIS7) to PWM value for parachute "OFF" position (usually between 700 and 1000ms)
- Set [PWM_MAIN_FAIL7](../advanced_config/parameter_reference.md#PWM_MAIN_FAIL7) to PWM value for parachute "ON" position (usually between 1800 and 2200ms)
You then need to ensure that the parachute pin will be set to a value that will trigger the parachute when a failsafe occurs.

Motor settings:
- Set [PWM_MAIN_FAILn](../advanced_config/parameter_reference.md#PWM_MAIN_FAIL1), where n is 1 - 4, to 900ms such that the motors directly go to disarmed values.
In PX4 v1.13 (by default) and earlier:

- Set [PWM_AUX_DIS6](../advanced_config/parameter_reference.md#PWM_AUX_DIS6) to PWM value for parachute "OFF" position (usually between 700 and 1000ms)
- Set [PWM_AUX_DIS6](../advanced_config/parameter_reference.md#PWM_AUX_DIS6) to PWM value for parachute "ON" position (usually between 1800 and 2200ms)

:::note
There is no way to recover from a Termination state!
Reboot/power cycle the vehicle before your next test.
The above values would be suitable for this spring-loaded launcher from [Fruity Chutes](https://fruitychutes.com/buyachute/drone-and-uav-parachute-recovery-c-21/harrier-drone-parachute-launcher-c-21_33/).
You will need to use values appropriate for your parachute.
:::

<span id="testing"></span>
If dynamic control allocation is enabled ([SYS_CTRL_ALLOC=1](../advanced_config/parameter_reference.md#SYS_CTRL_ALLOC)):
- Open [Actuators](../config/actuators.md) in QGroundControl
- Assign the _Parachute_ function to the `AUX6` output:

![Actuators - Parachute (QGC)](../../assets/config/actuators/qgc_actuators_parachute.png)
- Set appropriate PWM values.
The output is automatically set to the maximum PWM value when a failsafe is triggered.



### MAVLink Parachute Setup

PX4 will trigger a connected and healthy parachute on failsafe by sending the command [MAV_CMD_DO_PARACHUTE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_PARACHUTE) with the [PARACHUTE_RELEASE](https://mavlink.io/en/messages/common.html#PARACHUTE_ACTION) action.

MAVLink parachute support is enabled by setting the parameter [COM_PARACHUTE=1](../advanced_config/parameter_reference.md#COM_PARACHUTE).
PX4 will then indicate parachute status using the [MAV_SYS_STATUS_RECOVERY_SYSTEM](https://mavlink.io/en/messages/common.html#MAV_SYS_STATUS_RECOVERY_SYSTEM) bit in the [SYS_STATUS](https://mavlink.io/en/messages/common.html#SYS_STATUS) extended onboard control sensors fields:
- `SYS_STATUS.onboard_control_sensors_present_extended`: MAVLink parachute present (based on heartbeat detection).
- `SYS_STATUS.onboard_control_sensors_enabled_extended`: ?
- `SYS_STATUS.onboard_control_sensors_health_extended`: MAVLink parachute healthy (based on heartbeat detection).

A MAVLink parachute is required to emit a [HEARTBEAT](https://mavlink.io/en/messages/common.html#HEARTBEAT) with `HEARTBEAT.type` of [MAV_TYPE_PARACHUTE](https://mavlink.io/en/messages/common.html#MAV_TYPE_PARACHUTE).

<!-- PX4 v1.13 support added here: https://github.com/PX4/PX4-Autopilot/pull/18589 -->

## Parachute Testing

:::warning
For the first test, try on the bench, without the props and with an unloaded parachute device!
:::

:::note
There is no way to recover from a Termination state!
You will need to reboot/power cycle the vehicle for subsequent tests.
:::

The parachute will trigger during [flight termination](../advanced_config/flight_termination.md).

The easiest way to test a (real) parachute is to enable the [failure detector attitude trigger](../config/safety.md#attitude-trigger) and tip the vehicle over.

You can also simulate a parachute/flight termination in Gazebo: [Development > Simulation > Gazebo > Simulated Parachute/Flight Termination](../simulation/gazebo.md#flight_termination).

0 comments on commit 883ad47

Please sign in to comment.