mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: correct call for getting location vector
Function has been renamed and only takes a Vector2f
This commit is contained in:
parent
302e5c6871
commit
dff27ec506
|
@ -1237,9 +1237,9 @@ bool AC_WPNav::get_terrain_offset(float& offset_cm)
|
|||
// returns false if conversion failed (likely because terrain data was not available)
|
||||
bool AC_WPNav::get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &terrain_alt)
|
||||
{
|
||||
// convert location to NEU vector3f
|
||||
Vector3f res_vec;
|
||||
if (!loc.get_vector_xy_from_origin_NEU(res_vec)) {
|
||||
// convert location to NE vector2f
|
||||
Vector2f res_vec;
|
||||
if (!loc.get_vector_xy_from_origin_NE(res_vec)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue