ArduCopter: set AUTO_YAW_HOLD when user control yaw during nogps land

This commit is contained in:
Pierre Kancir 2018-06-01 12:14:58 +02:00 committed by Randy Mackay
parent c2811ea144
commit d5d81f3a1c
1 changed files with 3 additions and 0 deletions

View File

@ -102,6 +102,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);
}
}
// disarm when the landing detector says we've landed