Skip to content

Commit

Permalink
AP_Parachute: fixed build
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Aug 2, 2024
1 parent ab2df43 commit d8a189f
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 5 deletions.
4 changes: 1 addition & 3 deletions libraries/AP_Parachute/AP_Parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
};
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Parachute/AP_Parachute.h
Original file line number Diff line number Diff line change
Expand Up @@ -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[];

Expand Down

0 comments on commit d8a189f

Please sign in to comment.