diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 3c9b8c9796..8997f099b4 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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 diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 7f18801a74..2a01afa70f 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -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;