From 2cc9f1463ea1231f533825535eb1d0538740c8dd Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 24 Aug 2022 16:05:50 +0200 Subject: [PATCH] Copter: disable TKOFF_RPM_MIN on Heli --- ArduCopter/Parameters.cpp | 2 ++ ArduCopter/takeoff_check.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index c13eb4af7c..73c1b1f763 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1151,12 +1151,14 @@ 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 // @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 // @Range: 0 10000 // @User: Standard AP_GROUPINFO("TKOFF_RPM_MIN", 58, ParametersG2, takeoff_rpm_min, 0), +#endif // ID 62 is reserved for the SHOW_... parameters from the Skybrush fork at // https://github.com/skybrush-io/ardupilot diff --git a/ArduCopter/takeoff_check.cpp b/ArduCopter/takeoff_check.cpp index 8ee0df6c62..f3b55ec45f 100644 --- a/ArduCopter/takeoff_check.cpp +++ b/ArduCopter/takeoff_check.cpp @@ -7,7 +7,7 @@ // detects if the vehicle should be allowed to takeoff or not and sets the motors.blocked flag void Copter::takeoff_check() { -#if HAL_WITH_ESC_TELEM +#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME // If takeoff check is disabled or vehicle is armed and flying then clear block and return if ((g2.takeoff_rpm_min <= 0) || (motors->armed() && !ap.land_complete)) { motors->set_spoolup_block(false);