Plane: tilitrotor: allow motor test

This commit is contained in:
Peter Hall 2020-01-19 16:46:36 +00:00 committed by Andrew Tridgell
parent 90494c9de6
commit 807c05c715
1 changed files with 6 additions and 3 deletions

View File

@ -75,11 +75,13 @@ void QuadPlane::tiltrotor_continuous_update(void)
if (!hal.util->get_soft_armed()) {
tilt.current_throttle = 0;
} else {
// prevent motor shutdown
tilt.motors_active = true;
}
if (!motor_test.running) {
// the motors are all the way forward, start using them for fwd thrust
uint8_t mask = is_zero(tilt.current_throttle)?0:(uint8_t)tilt.tilt_mask.get();
motors->output_motor_mask(tilt.current_throttle, mask, plane.rudder_dt);
// prevent motor shutdown
tilt.motors_active = true;
}
return;
}
@ -373,7 +375,8 @@ void QuadPlane::tiltrotor_vectored_yaw(void)
*/
void QuadPlane::tiltrotor_bicopter(void)
{
if (tilt.tilt_type != TILT_TYPE_BICOPTER) {
if (tilt.tilt_type != TILT_TYPE_BICOPTER || motor_test.running) {
// don't override motor test with motors_output
return;
}