mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: check motor spool state in vtol approach check
This commit is contained in:
parent
1135a91846
commit
7b6d74be13
@ -2697,7 +2697,8 @@ void QuadPlane::update_throttle_thr_mix(void)
|
||||
bool QuadPlane::in_vtol_land_approach(void) const
|
||||
{
|
||||
if (in_vtol_auto() && is_vtol_land(plane.mission.get_current_nav_cmd().id) &&
|
||||
(poscontrol.state == QPOS_POSITION1 || poscontrol.state == QPOS_POSITION2)) {
|
||||
(poscontrol.state == QPOS_POSITION1 || poscontrol.state == QPOS_POSITION2) &&
|
||||
motors->get_desired_spool_state() >= AP_Motors::DESIRED_SPIN_WHEN_ARMED) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user