mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AC_WPNav: constify get_wp_destination
This commit is contained in:
parent
53f8aa2b92
commit
6361a9a204
@ -173,7 +173,8 @@ bool AC_WPNav::set_wp_destination(const Location& destination)
|
||||
return set_wp_destination(dest_neu, terr_alt);
|
||||
}
|
||||
|
||||
bool AC_WPNav::get_wp_destination(Location& destination) {
|
||||
bool AC_WPNav::get_wp_destination(Location& destination) const
|
||||
{
|
||||
Vector3f dest = get_wp_destination();
|
||||
if (!AP::ahrs().get_origin(destination)) {
|
||||
return false;
|
||||
|
@ -104,7 +104,7 @@ public:
|
||||
// returns wp location using location class.
|
||||
// returns false if unable to convert from target vector to global
|
||||
// coordinates
|
||||
bool get_wp_destination(Location& destination);
|
||||
bool get_wp_destination(Location& destination) const;
|
||||
|
||||
/// set_wp_destination waypoint using position vector (distance from ekf origin in cm)
|
||||
/// terrain_alt should be true if destination.z is a desired altitude above terrain
|
||||
|
Loading…
Reference in New Issue
Block a user