mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APMrover2: use past_interval_finish_line and line_path_proportion from Location
This commit is contained in:
parent
1854681e09
commit
f91ffffca7
@ -44,7 +44,7 @@ void ModeAuto::update()
|
||||
_distance_to_destination = rover.current_loc.get_distance(_destination);
|
||||
const bool near_wp = _distance_to_destination <= rover.g.waypoint_radius;
|
||||
// check if we've reached the destination
|
||||
if (!_reached_destination && (near_wp || location_passed_point(rover.current_loc, _origin, _destination))) {
|
||||
if (!_reached_destination && (near_wp || rover.current_loc.past_interval_finish_line(_origin, _destination))) {
|
||||
// trigger reached
|
||||
_reached_destination = true;
|
||||
}
|
||||
|
@ -21,7 +21,7 @@ void ModeGuided::update()
|
||||
_distance_to_destination = rover.current_loc.get_distance(_destination);
|
||||
const bool near_wp = _distance_to_destination <= rover.g.waypoint_radius;
|
||||
// check if we've reached the destination
|
||||
if (!_reached_destination && (near_wp || location_passed_point(rover.current_loc, _origin, _destination))) {
|
||||
if (!_reached_destination && (near_wp || rover.current_loc.past_interval_finish_line(_origin, _destination))) {
|
||||
_reached_destination = true;
|
||||
rover.gcs().send_mission_item_reached_message(0);
|
||||
}
|
||||
|
@ -28,7 +28,7 @@ void ModeRTL::update()
|
||||
_distance_to_destination = rover.current_loc.get_distance(_destination);
|
||||
const bool near_wp = _distance_to_destination <= rover.g.waypoint_radius;
|
||||
// check if we've reached the destination
|
||||
if (!_reached_destination && (near_wp || location_passed_point(rover.current_loc, _origin, _destination))) {
|
||||
if (!_reached_destination && (near_wp || rover.current_loc.past_interval_finish_line(_origin, _destination))) {
|
||||
// trigger reached
|
||||
_reached_destination = true;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached destination");
|
||||
|
@ -60,7 +60,7 @@ void ModeSmartRTL::update()
|
||||
}
|
||||
// check if we've reached the next point
|
||||
_distance_to_destination = rover.current_loc.get_distance(_destination);
|
||||
if (_distance_to_destination <= rover.g.waypoint_radius || location_passed_point(rover.current_loc, _origin, _destination)) {
|
||||
if (_distance_to_destination <= rover.g.waypoint_radius || rover.current_loc.past_interval_finish_line(_origin, _destination)) {
|
||||
_load_point = true;
|
||||
}
|
||||
// continue driving towards destination
|
||||
|
Loading…
Reference in New Issue
Block a user