mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Altitude no longer resets when moving loiter WP
This commit is contained in:
parent
7468889bb7
commit
0f24860552
@ -1689,7 +1689,8 @@ static void update_navigation()
|
|||||||
wp_control = NO_NAV_MODE;
|
wp_control = NO_NAV_MODE;
|
||||||
|
|
||||||
// reset LOITER to current position
|
// reset LOITER to current position
|
||||||
next_WP = current_loc;
|
next_WP.lat = current_loc.lat;
|
||||||
|
next_WP.lng = current_loc.lng;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// this is also set by GPS in update_nav
|
// this is also set by GPS in update_nav
|
||||||
|
Loading…
Reference in New Issue
Block a user