Rover: fix auto mode distance_to_destination

This commit is contained in:
Randy Mackay 2017-12-09 12:32:53 +09:00
parent 9b81c133f6
commit 4958298a75
2 changed files with 10 additions and 1 deletions

View File

@ -194,7 +194,7 @@ public:
bool is_autopilot_mode() const override { return true; }
// return distance (in meters) to destination
float get_distance_to_destination() const override { return _distance_to_destination; }
float get_distance_to_destination() const override;
// set desired location, heading and speed
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN);

View File

@ -87,6 +87,15 @@ void ModeAuto::update()
}
}
// return distance (in meters) to destination
float ModeAuto::get_distance_to_destination() const
{
if (_submode == Auto_RTL) {
return _mode_rtl.get_distance_to_destination();
}
return _distance_to_destination;
}
// set desired location to drive to
void ModeAuto::set_desired_location(const struct Location& destination, float next_leg_bearing_cd)
{