Plane: don't yaw quad when disarming

This commit is contained in:
Andrew Tridgell 2016-01-02 15:16:31 +11:00
parent ecd7d53cfc
commit f5a15fb7c5

View File

@ -546,6 +546,10 @@ float QuadPlane::get_pilot_desired_yaw_rate_cds(void)
// use bank angle to get desired yaw rate
return desired_yaw_rate_cds();
}
if (plane.channel_throttle->control_in <= 0) {
// the user may be trying to disarm
return 0;
}
const float yaw_rate_max_dps = 100;
return plane.channel_rudder->norm_input() * 100 * yaw_rate_max_dps;
}