Plane: added turn corrdination to autotune yaw rate tuning
this makes it much easier to do a yaw rate autotune, and also means you don't need to use the rudder stick at all, as the yaw controller is already exercised nicely with roll movements, so overall the tune is faster and more accurate as less cross-axis coupling
This commit is contained in:
parent
502e28e8bc
commit
3579cb451d
@ -618,7 +618,9 @@ void Plane::calc_nav_yaw_coordinated(float speed_scaler)
|
||||
// user is doing an AUTOTUNE with yaw rate control
|
||||
const float rudd_expo = rudder_in_expo(true);
|
||||
const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate;
|
||||
commanded_rudder = yawController.get_rate_out(yaw_rate, speed_scaler, false);
|
||||
// add in the corrdinated turn yaw rate to make it easier to fly while tuning the yaw rate controller
|
||||
const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(radians(nav_roll_cd*0.01f))/MAX(aparm.airspeed_min,smoothed_airspeed));
|
||||
commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false);
|
||||
using_rate_controller = true;
|
||||
} else {
|
||||
if (control_mode == &mode_stabilize && rudder_in != 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user