Browse Source

ArduCopter: set AUTO_YAW_HOLD when user control yaw during nogps land

master
Pierre Kancir 7 years ago committed by Randy Mackay
parent
commit
d5d81f3a1c
  1. 3
      ArduCopter/mode_land.cpp

3
ArduCopter/mode_land.cpp

@ -102,6 +102,9 @@ void Copter::ModeLand::nogps_run() @@ -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

Loading…
Cancel
Save