mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Motors: support twin-motor tailsitters
use differential thrust for roll
This commit is contained in:
parent
b3380ecfa7
commit
83d055eceb
@ -64,6 +64,13 @@ void AP_MotorsTailsitter::output_to_motors()
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, _elevator*SERVO_OUTPUT_RANGE);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, _rudder*SERVO_OUTPUT_RANGE);
|
||||
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);
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
SRV_Channels::calc_pwm();
|
||||
SRV_Channels::output_ch_all();
|
||||
|
Loading…
Reference in New Issue
Block a user