mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: added waypoint passed logic to RTL
this prevents circling around home
This commit is contained in:
parent
d02a127b7e
commit
0ed3061d32
@ -222,9 +222,16 @@ static bool verify_RTL()
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("Reached home"));
|
||||
rtl_complete = true;
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
}
|
||||
|
||||
// have we gone past the waypoint?
|
||||
if (location_passed_point(current_loc, prev_WP, next_WP)) {
|
||||
gcs_send_text_fmt(PSTR("Reached Home dist %um"),
|
||||
(unsigned)get_distance(¤t_loc, &next_WP));
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
|
Loading…
Reference in New Issue
Block a user