mirror of https://github.com/ArduPilot/ardupilot
Plane: added in FF component in tailsitters
this is needed for decent control of tailsitters
This commit is contained in:
parent
ea3657e941
commit
b984dd4a62
|
@ -164,9 +164,9 @@ void QuadPlane::tailsitter_output(void)
|
|||
plane.rollController.reset_I();
|
||||
|
||||
// pull in copter control outputs
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, (motors->get_yaw())*-SERVO_MAX);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, (motors->get_pitch())*SERVO_MAX);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, (motors->get_roll())*SERVO_MAX);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, (motors->get_yaw()+motors->get_yaw_ff())*-SERVO_MAX);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, (motors->get_pitch()+motors->get_pitch_ff())*SERVO_MAX);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, (motors->get_roll()+motors->get_roll_ff())*SERVO_MAX);
|
||||
|
||||
if (hal.util->get_soft_armed()) {
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, motors->thrust_to_actuator(motors->get_throttle()) * 100);
|
||||
|
|
Loading…
Reference in New Issue