From dc2e04dc851a3cb029835114046a1ee4bdd7474d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?J=C4=99drzej=20Stasik?= Date: Fri, 12 Jul 2024 08:51:14 +0200 Subject: [PATCH] fix: make CHUTE_TIMEOUT only for Copter --- libraries/AP_Parachute/AP_Parachute.cpp | 2 ++ libraries/AP_Parachute/AP_Parachute.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index c08e1a500d..d929145994 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -83,6 +83,7 @@ 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 @@ -90,6 +91,7 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = { // @Range: 0.5 5.0 // @User: Advanced AP_GROUPINFO("TIMEOUT", 8, AP_Parachute, _timeout, AP_PARACHUTE_TIMEOUT_DEFAULT), +#endif AP_GROUPEND }; diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index eba5cc3bff..8a96105111 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -91,8 +91,10 @@ public: // 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[];