mirror of https://github.com/ArduPilot/ardupilot
Plane: Training: output rudder from mode run function
This commit is contained in:
parent
9a68b78973
commit
f89563f987
|
@ -63,5 +63,10 @@ void ModeTraining::run()
|
|||
}
|
||||
}
|
||||
|
||||
plane.stabilize_yaw();
|
||||
// Always manual rudder control
|
||||
const float pilot_rudder = plane.rudder_in_expo(false);
|
||||
plane.steering_control.rudder = pilot_rudder;
|
||||
plane.steering_control.steering = pilot_rudder;
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, pilot_rudder);
|
||||
|
||||
}
|
||||
|
|
|
@ -837,10 +837,7 @@ void Plane::set_servos(void)
|
|||
// clear ground_steering to ensure manual control if the yaw stabilizer doesn't run
|
||||
steering_control.ground_steering = false;
|
||||
|
||||
if (control_mode == &mode_training) {
|
||||
steering_control.rudder = rudder_in_expo(false);
|
||||
}
|
||||
|
||||
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_control.rudder);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_control.steering);
|
||||
|
||||
|
|
Loading…
Reference in New Issue