Copter: fix landing detector for autorotation

This commit is contained in:
Bill Geyer 2023-01-21 22:33:21 -05:00 committed by Bill Geyer
parent 128794ec84
commit b24a6fe15f

View File

@ -73,6 +73,9 @@ void Copter::update_land_detector()
// check if landing
const bool landing = flightmode->is_landing();
bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll()) < M_PI/2.0f)
#if MODE_AUTOROTATE_ENABLED == ENABLED
|| (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll())
#endif
|| ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f);
bool throttle_mix_at_min = true;
#else