Browse Source

Copter: enable precision landing in auto mode

master
Derek Ma 9 years ago committed by Randy Mackay
parent
commit
7fddf20f0b
  1. 6
      ArduCopter/control_auto.cpp

6
ArduCopter/control_auto.cpp

@ -420,6 +420,12 @@ void Copter::auto_land_run() @@ -420,6 +420,12 @@ void Copter::auto_land_run()
// process roll, pitch inputs
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
#if PRECISION_LANDING == ENABLED
// run precision landing
if (!ap.land_repo_active) {
wp_nav.shift_loiter_target(precland.get_target_shift(wp_nav.get_loiter_target()));
}
#endif
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);

Loading…
Cancel
Save