From d8a189fb313008401e819a5977ab21e4092777c5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 3 Aug 2024 07:26:39 +1000 Subject: [PATCH] AP_Parachute: fixed build --- libraries/AP_Parachute/AP_Parachute.cpp | 4 +--- libraries/AP_Parachute/AP_Parachute.h | 2 -- 2 files changed, 1 insertion(+), 5 deletions(-) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index d9291459944fb..cb1ab1b520f04 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -83,15 +83,13 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = { // @User: Standard AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, AP_PARACHUTE_OPTIONS_DEFAULT), -#if APM_BUILD_COPTER_OR_HELI // @Param: TIMEOUT // @DisplayName: Parachute timeout // @Description: Triggers the parachute if the loss of control lasts for the time specified by this parameter // @Units: s // @Range: 0.5 5.0 // @User: Advanced - AP_GROUPINFO("TIMEOUT", 8, AP_Parachute, _timeout, AP_PARACHUTE_TIMEOUT_DEFAULT), -#endif + AP_GROUPINFO_FRAME("TIMEOUT", 8, AP_Parachute, _timeout, AP_PARACHUTE_TIMEOUT_DEFAULT, AP_PARAM_FRAME_COPTER), AP_GROUPEND }; diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index 8a96105111381..eba5cc3bff5cf 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -91,10 +91,8 @@ class AP_Parachute { // Return the relay index that would be used for param conversion to relay functions bool get_legacy_relay_index(int8_t &index) const; -#if APM_BUILD_COPTER_OR_HELI // Return the CHUTE_TIMEOUT parameter value float get_chute_timeout() const { return _timeout; } -#endif static const struct AP_Param::GroupInfo var_info[];