mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: Missing Loiter Init on accel
This commit is contained in:
parent
9cd1be1d6f
commit
1b5b46dab5
@ -829,6 +829,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;
|
||||
}
|
||||
@ -924,6 +925,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
Block a user