mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Motors: force roll motors to 0 in tailsitter when disarmed
This commit is contained in:
parent
b15b11e32d
commit
6f54eef857
@ -49,6 +49,9 @@ void AP_MotorsTailsitter::output_to_motors()
|
||||
if (!_flags.initialised_ok) {
|
||||
return;
|
||||
}
|
||||
float throttle_left = 0;
|
||||
float throttle_right = 0;
|
||||
|
||||
switch (_spool_mode) {
|
||||
case SHUT_DOWN:
|
||||
_throttle = 0;
|
||||
@ -60,6 +63,8 @@ void AP_MotorsTailsitter::output_to_motors()
|
||||
case SPOOL_UP:
|
||||
case THROTTLE_UNLIMITED:
|
||||
case SPOOL_DOWN:
|
||||
throttle_left = constrain_float(_throttle + _rudder*0.5, 0, 1);
|
||||
throttle_right = constrain_float(_throttle - _rudder*0.5, 0, 1);
|
||||
break;
|
||||
}
|
||||
// outputs are setup here, and written to the HAL by the plane servos loop
|
||||
@ -69,8 +74,6 @@ void AP_MotorsTailsitter::output_to_motors()
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, _throttle*THROTTLE_RANGE);
|
||||
|
||||
// also support differential roll with twin motors
|
||||
float throttle_left = constrain_float(_throttle + _rudder*0.5, 0, 1);
|
||||
float throttle_right = constrain_float(_throttle - _rudder*0.5, 0, 1);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left*THROTTLE_RANGE);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right*THROTTLE_RANGE);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user