Copter: disable TKOFF_RPM_MIN on Heli

This commit is contained in:
Andy Piper 2022-08-24 16:05:50 +02:00 committed by Peter Hall
parent 203f691df4
commit 2cc9f1463e
2 changed files with 3 additions and 1 deletions

View File

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

View File

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