mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
TradHeli: Stabilize mode should use get_pilot_desired_collective, not get_pilot_desired_throttle.
This commit is contained in:
parent
032f321348
commit
5b13b2b3da
@ -34,7 +34,7 @@ static void heli_stabilize_run()
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
|
||||
// get pilot's desired throttle
|
||||
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
|
||||
pilot_throttle_scaled = get_pilot_desired_collective(g.rc_3.control_in);
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
|
Loading…
Reference in New Issue
Block a user