AP_Navigation: avoid using struct Location

clang reports this could be a problem when compiling under some EABIs.  Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
Peter Barker 2023-02-03 09:58:39 +11:00 committed by Peter Barker
parent 35a5a73f52
commit 0c7ac5dd12
1 changed files with 2 additions and 2 deletions

View File

@ -67,7 +67,7 @@ public:
// main flight code will call an output function (such as
// nav_roll_cd()) after this function to ask for the new required
// navigation attitude/steering.
virtual void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min = 0.0f) = 0;
virtual void update_waypoint(const class Location &prev_WP, const class Location &next_WP, float dist_min = 0.0f) = 0;
// update the internal state of the navigation controller for when
// the vehicle has been commanded to circle about a point. This
@ -76,7 +76,7 @@ public:
// main flight code will call an output function (such as
// nav_roll_cd()) after this function to ask for the new required
// navigation attitude/steering.
virtual void update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction) = 0;
virtual void update_loiter(const class Location &center_WP, float radius, int8_t loiter_direction) = 0;
// update the internal state of the navigation controller, given a
// fixed heading. This is the step function for navigation control