Skip to content

Commit

Permalink
fix: make CHUTE_TIMEOUT only for Copter
Browse files Browse the repository at this point in the history
  • Loading branch information
Sztosik committed Jul 12, 2024
1 parent cd5f3ec commit 03cde35
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 0 deletions.
2 changes: 2 additions & 0 deletions libraries/AP_Parachute/AP_Parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,13 +83,15 @@ 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_GROUPEND
};
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Parachute/AP_Parachute.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,10 @@ 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[];

Expand Down

0 comments on commit 03cde35

Please sign in to comment.