mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: Parameter ACRO_THR_MID is only used in ACRO flight mode
This commit is contained in:
parent
9de1813ae6
commit
4f0cf6d334
@ -899,12 +899,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ACRO_Y_EXPO", 9, ParametersG2, acro_y_expo, ACRO_Y_EXPO_DEFAULT),
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
// @Param: ACRO_THR_MID
|
||||
// @DisplayName: Acro Thr Mid
|
||||
// @Description: Acro Throttle Mid
|
||||
// @Range: 0 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ACRO_THR_MID", 10, ParametersG2, acro_thr_mid, ACRO_THR_MID_DEFAULT),
|
||||
#endif
|
||||
|
||||
// @Param: SYSID_ENFORCE
|
||||
// @DisplayName: GCS sysid enforcement
|
||||
|
@ -552,7 +552,9 @@ public:
|
||||
|
||||
// acro exponent parameters
|
||||
AP_Float acro_y_expo;
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
AP_Float acro_thr_mid;
|
||||
#endif
|
||||
|
||||
// frame class
|
||||
AP_Int8 frame_class;
|
||||
|
Loading…
Reference in New Issue
Block a user