mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AC_WPNav: fix reporting of set_wp_destination failure
This commit is contained in:
parent
9fbfea951a
commit
e23c869c5d
@ -439,9 +439,7 @@ bool AC_WPNav::set_wp_destination(const Location_Class& destination)
|
||||
}
|
||||
|
||||
// set target as vector from EKF origin
|
||||
set_wp_destination(dest_neu, terr_alt);
|
||||
|
||||
return true;
|
||||
return set_wp_destination(dest_neu, terr_alt);
|
||||
}
|
||||
|
||||
/// set_wp_destination waypoint using position vector (distance from home in cm)
|
||||
|
Loading…
Reference in New Issue
Block a user