mirror of https://github.com/ArduPilot/ardupilot
AR_WPNav: add is_destination_valid accessor
This commit is contained in:
parent
17060d5d66
commit
ce44d127c0
|
@ -51,6 +51,9 @@ public:
|
|||
// return distance (in meters) to destination
|
||||
float get_distance_to_destination() const { return _distance_to_destination; }
|
||||
|
||||
// return true if destination is valid
|
||||
bool is_destination_valid() const { return _orig_and_dest_valid; }
|
||||
|
||||
// get current destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked)
|
||||
const Location &get_destination() { return _destination; }
|
||||
|
||||
|
|
Loading…
Reference in New Issue