Copter: Missing Loiter Init on accel

This commit is contained in:
Leonard Hall 2018-09-19 12:20:37 +09:30 committed by Andrew Tridgell
parent 870db7d714
commit 93c0568d07
1 changed files with 2 additions and 0 deletions

View File

@ -864,6 +864,7 @@ void Copter::ModeAuto::land_run()
if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) { if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
zero_throttle_and_relax_ac(); zero_throttle_and_relax_ac();
// set target to current position // set target to current position
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
return; return;
} }
@ -959,6 +960,7 @@ void Copter::ModeAuto::payload_place_run()
if (!payload_place_run_should_run()) { if (!payload_place_run_should_run()) {
zero_throttle_and_relax_ac(); zero_throttle_and_relax_ac();
// set target to current position // set target to current position
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target(); loiter_nav->init_target();
return; return;
} }