mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
Plane: don't yaw quad when disarming
This commit is contained in:
parent
ecd7d53cfc
commit
f5a15fb7c5
@ -546,6 +546,10 @@ float QuadPlane::get_pilot_desired_yaw_rate_cds(void)
|
|||||||
// use bank angle to get desired yaw rate
|
// use bank angle to get desired yaw rate
|
||||||
return desired_yaw_rate_cds();
|
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;
|
const float yaw_rate_max_dps = 100;
|
||||||
return plane.channel_rudder->norm_input() * 100 * yaw_rate_max_dps;
|
return plane.channel_rudder->norm_input() * 100 * yaw_rate_max_dps;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user