mirror of https://github.com/ArduPilot/ardupilot
AR_WPNav: 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:
parent
0c7ac5dd12
commit
517e42c678
|
@ -199,7 +199,7 @@ void AR_WPNav::set_nudge_speed_max(float nudge_speed_max)
|
|||
|
||||
// set desired location and (optionally) next_destination
|
||||
// next_destination should be provided if known to allow smooth cornering
|
||||
bool AR_WPNav::set_desired_location(const struct Location& destination, Location next_destination)
|
||||
bool AR_WPNav::set_desired_location(const Location& destination, Location next_destination)
|
||||
{
|
||||
// re-initialise if inactive, previous destination has been interrupted or different controller was used
|
||||
if (!is_active() || !_reached_destination || (_nav_control_type != NavControllerType::NAV_SCURVE)) {
|
||||
|
|
|
@ -137,7 +137,7 @@ void AR_WPNav_OA::update(float dt)
|
|||
|
||||
// set desired location and (optionally) next_destination
|
||||
// next_destination should be provided if known to allow smooth cornering
|
||||
bool AR_WPNav_OA::set_desired_location(const struct Location& destination, Location next_destination)
|
||||
bool AR_WPNav_OA::set_desired_location(const Location& destination, Location next_destination)
|
||||
{
|
||||
const bool ret = AR_WPNav::set_desired_location(destination, next_destination);
|
||||
|
||||
|
|
Loading…
Reference in New Issue