Rover: boats keep navigating at WP if loiter fails

This commit is contained in:
Randy Mackay 2023-11-28 08:16:12 +09:00
parent f3868cf463
commit 2b2f92b654

View File

@ -77,13 +77,13 @@ void ModeAuto::update()
case Auto_WP: case Auto_WP:
{ {
// boats loiter once the waypoint is reached // boats loiter once the waypoint is reached
bool keep_navigating = true;
if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) { if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) {
start_loiter(); keep_navigating = !start_loiter();
}
// update distance to destination
_distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination());
} else {
// update navigation controller // update navigation controller
if (keep_navigating) {
navigate_to_waypoint(); navigate_to_waypoint();
} }
break; break;