fix: make CHUTE_TIMEOUT only for Copter

This commit is contained in:
Jędrzej Stasik 2024-07-12 08:51:14 +02:00 committed by Andrew Tridgell
parent abd43aea59
commit dc2e04dc85
2 changed files with 4 additions and 0 deletions

View File

@ -83,6 +83,7 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, AP_PARACHUTE_OPTIONS_DEFAULT), AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, AP_PARACHUTE_OPTIONS_DEFAULT),
#if APM_BUILD_COPTER_OR_HELI
// @Param: TIMEOUT // @Param: TIMEOUT
// @DisplayName: Parachute timeout // @DisplayName: Parachute timeout
// @Description: Triggers the parachute if the loss of control lasts for the time specified by this parameter // @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 // @Range: 0.5 5.0
// @User: Advanced // @User: Advanced
AP_GROUPINFO("TIMEOUT", 8, AP_Parachute, _timeout, AP_PARACHUTE_TIMEOUT_DEFAULT), AP_GROUPINFO("TIMEOUT", 8, AP_Parachute, _timeout, AP_PARACHUTE_TIMEOUT_DEFAULT),
#endif
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -91,8 +91,10 @@ public:
// Return the relay index that would be used for param conversion to relay functions // Return the relay index that would be used for param conversion to relay functions
bool get_legacy_relay_index(int8_t &index) const; bool get_legacy_relay_index(int8_t &index) const;
#if APM_BUILD_COPTER_OR_HELI
// Return the CHUTE_TIMEOUT parameter value // Return the CHUTE_TIMEOUT parameter value
float get_chute_timeout() const { return _timeout; } float get_chute_timeout() const { return _timeout; }
#endif
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];