diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 73c1b1f763..7ada4605d5 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1151,7 +1151,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("TKOFF_SLEW_TIME", 57, ParametersG2, takeoff_throttle_slew_time, 2.0), -#if FRAME_CONFIG != HELI_FRAME +#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME // @Param: TKOFF_RPM_MIN // @DisplayName: Takeoff Check RPM minimum // @Description: Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 07c4822a0b..2f7221cec5 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -670,7 +670,9 @@ public: // ramp time of throttle during take-off AP_Float takeoff_throttle_slew_time; - AP_Int16 takeoff_rpm_min; +#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME + AP_Int16 takeoff_rpm_min; +#endif }; extern const AP_Param::Info var_info[];