Plane: quadplane: pass time to tailsitter.in_vtol_transition where avalable

This commit is contained in:
Peter Hall 2021-11-10 02:14:28 +00:00 committed by Andrew Tridgell
parent 9634641323
commit 67d7ba490f

View File

@ -1864,7 +1864,8 @@ void QuadPlane::motors_output(bool run_rate_controller)
return;
}
if (tailsitter.in_vtol_transition() && !assisted_flight) {
const uint32_t now = AP_HAL::millis();
if (tailsitter.in_vtol_transition(now) && !assisted_flight) {
/*
don't run the motor outputs while in tailsitter->vtol
transition. That is taken care of by the fixed wing
@ -1873,7 +1874,6 @@ void QuadPlane::motors_output(bool run_rate_controller)
return;
}
const uint32_t now = AP_HAL::millis();
if (run_rate_controller) {
if (now - last_att_control_ms > 100) {
// relax if have been inactive
@ -2319,7 +2319,7 @@ void QuadPlane::vtol_position_controller(void)
case QPOS_POSITION1: {
setup_target_position();
if (tailsitter.enabled() && tailsitter.in_vtol_transition()) {
if (tailsitter.enabled() && tailsitter.in_vtol_transition(now_ms)) {
break;
}
@ -2488,7 +2488,7 @@ void QuadPlane::vtol_position_controller(void)
}
break;
case QPOS_POSITION1:
if (tailsitter.in_vtol_transition()) {
if (tailsitter.in_vtol_transition(now_ms)) {
pos_control->relax_z_controller(0);
break;
}