mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Copter: updated toy gains
This commit is contained in:
parent
1c7d9f43c1
commit
66b8ca3a27
@ -14,8 +14,8 @@ get_yaw_toy()
|
||||
// Gain scheduling for Yaw input -
|
||||
// we reduce the yaw input based on the velocity of the copter
|
||||
// 0 = full control, 600cm/s = 20% control
|
||||
toy_gain = min(inertial_nav.get_velocity_xy(), 600);
|
||||
toy_gain = 1.0 - (toy_gain / 750.0);
|
||||
toy_gain = min(inertial_nav.get_velocity_xy(), 700);
|
||||
toy_gain = 1.0 - (toy_gain / 800.0);
|
||||
get_yaw_rate_stabilized_ef((float)control_roll * toy_gain);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user