mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
Copter: control_loiter initialises alt target
This commit is contained in:
parent
6ba91369ff
commit
eec62cb16a
@ -10,6 +10,8 @@ static bool loiter_init(bool ignore_checks)
|
|||||||
if (GPS_ok() || ignore_checks) {
|
if (GPS_ok() || ignore_checks) {
|
||||||
// set target to current position
|
// set target to current position
|
||||||
wp_nav.init_loiter_target();
|
wp_nav.init_loiter_target();
|
||||||
|
// initialise altitude target to stopping point
|
||||||
|
pos_control.set_target_to_stopping_point_z();
|
||||||
return true;
|
return true;
|
||||||
}else{
|
}else{
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user