mirror of https://github.com/ArduPilot/ardupilot
Copter: Missing Loiter Init on accel
This commit is contained in:
parent
870db7d714
commit
93c0568d07
|
@ -864,6 +864,7 @@ void Copter::ModeAuto::land_run()
|
|||
if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
|
||||
zero_throttle_and_relax_ac();
|
||||
// set target to current position
|
||||
loiter_nav->clear_pilot_desired_acceleration();
|
||||
loiter_nav->init_target();
|
||||
return;
|
||||
}
|
||||
|
@ -959,6 +960,7 @@ void Copter::ModeAuto::payload_place_run()
|
|||
if (!payload_place_run_should_run()) {
|
||||
zero_throttle_and_relax_ac();
|
||||
// set target to current position
|
||||
loiter_nav->clear_pilot_desired_acceleration();
|
||||
loiter_nav->init_target();
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue