mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Rover: verify_RTL calls rtl mode
also remove unused rtl_complete
This commit is contained in:
parent
1b19ee865d
commit
56b0621994
@ -264,8 +264,6 @@ private:
|
||||
// true if we have a position estimate from AHRS
|
||||
bool have_position;
|
||||
|
||||
bool rtl_complete;
|
||||
|
||||
// angle of our next navigation waypoint
|
||||
int32_t next_navigation_leg_cd;
|
||||
|
||||
|
@ -295,21 +295,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
bool Rover::verify_RTL()
|
||||
{
|
||||
if (wp_distance <= g.waypoint_radius) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached destination");
|
||||
rtl_complete = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// have we gone past the waypoint?
|
||||
if (location_passed_point(current_loc, prev_WP, next_WP)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached destination. Distance away %dm",
|
||||
static_cast<int32_t>(fabsf(get_distance(current_loc, next_WP))));
|
||||
rtl_complete = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
return mode_rtl.reached_destination();
|
||||
}
|
||||
|
||||
bool Rover::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
||||
|
Loading…
Reference in New Issue
Block a user