AR_WPNav: add is_fast_waypoint accessor

This commit is contained in:
Randy Mackay 2022-01-03 14:29:40 +09:00
parent 0bcae12ceb
commit e0a628bb8c

View File

@ -103,6 +103,9 @@ public:
// returns true on success, false on failure
bool get_stopping_location(Location& stopping_loc) WARN_IF_UNUSED;
// is_fast_waypoint returns true if vehicle will not stop at destination (e.g. set_desired_location provided a next_destination)
bool is_fast_waypoint() const { return _fast_waypoint; }
// parameter var table
static const struct AP_Param::GroupInfo var_info[];