mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
parent
603f061f58
commit
1e2e24eeac
@ -144,7 +144,7 @@ void Copter::throw_run()
|
||||
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f, get_smoothing_gain());
|
||||
|
||||
// output 50% throttle and turn off angle boost to maximise righting moment
|
||||
attitude_control.set_throttle_out(500, false, g.throttle_filt);
|
||||
attitude_control.set_throttle_out(0.5f, false, g.throttle_filt);
|
||||
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user