mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
ArduCopter: set AUTO_YAW_HOLD when user control yaw during nogps land
This commit is contained in:
parent
99e04e5861
commit
c55d19b287
@ -105,6 +105,9 @@ void Copter::ModeLand::nogps_run()
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
}
|
||||
|
||||
// if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
|
Loading…
Reference in New Issue
Block a user