Copter: takeoff rpm: define out if no ESC telem

This commit is contained in:
Iampete1 2022-09-06 15:00:07 +01:00 committed by Peter Hall
parent fce1fa6752
commit ee31f2322e
2 changed files with 4 additions and 2 deletions

View File

@ -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

View File

@ -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[];