AP_Parachute: make configurable in hwdef.dat

This commit is contained in:
Andrew Tridgell 2020-01-18 09:57:09 +11:00
parent 91b01a3eb2
commit c3263d057f
2 changed files with 12 additions and 0 deletions

View File

@ -1,4 +1,7 @@
#include "AP_Parachute.h"
#if HAL_PARACHUTE_ENABLED
#include <AP_Relay/AP_Relay.h>
#include <AP_Math/AP_Math.h>
#include <RC_Channel/RC_Channel.h>
@ -172,3 +175,4 @@ AP_Parachute *parachute()
}
}
#endif // HAL_PARACHUTE_ENABLED

View File

@ -22,6 +22,12 @@
#define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
#ifndef HAL_PARACHUTE_ENABLED
#define HAL_PARACHUTE_ENABLED !HAL_MINIMIZE_FEATURES
#endif
#if HAL_PARACHUTE_ENABLED
/// @class AP_Parachute
/// @brief Class managing the release of a parachute
class AP_Parachute {
@ -109,3 +115,5 @@ private:
namespace AP {
AP_Parachute *parachute();
};
#endif // HAL_PARACHUTE_ENABLED