mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Parachute: default to parachute enabled
This commit is contained in:
parent
d546877d3f
commit
77fab986ea
@ -23,7 +23,8 @@
|
|||||||
#define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
|
#define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
|
||||||
|
|
||||||
#ifndef HAL_PARACHUTE_ENABLED
|
#ifndef HAL_PARACHUTE_ENABLED
|
||||||
#define HAL_PARACHUTE_ENABLED !HAL_MINIMIZE_FEATURES
|
// default to parachute enabled to match previous configs
|
||||||
|
#define HAL_PARACHUTE_ENABLED 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAL_PARACHUTE_ENABLED
|
#if HAL_PARACHUTE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user