mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: fix auto mode distance_to_destination
This commit is contained in:
parent
9b81c133f6
commit
4958298a75
@ -194,7 +194,7 @@ public:
|
|||||||
bool is_autopilot_mode() const override { return true; }
|
bool is_autopilot_mode() const override { return true; }
|
||||||
|
|
||||||
// return distance (in meters) to destination
|
// 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
|
// set desired location, heading and speed
|
||||||
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN);
|
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN);
|
||||||
|
@ -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
|
// set desired location to drive to
|
||||||
void ModeAuto::set_desired_location(const struct Location& destination, float next_leg_bearing_cd)
|
void ModeAuto::set_desired_location(const struct Location& destination, float next_leg_bearing_cd)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user