mirror of https://github.com/ArduPilot/ardupilot
AP_Common: use Vector3f.xy() to avoid creating a fresh Vector2f
This commit is contained in:
parent
141074d07a
commit
04adfc814a
|
@ -219,12 +219,9 @@ bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
|
|||
bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
|
||||
{
|
||||
// convert lat, lon
|
||||
Vector2f vec_ne;
|
||||
if (!get_vector_xy_from_origin_NE(vec_ne)) {
|
||||
if (!get_vector_xy_from_origin_NE(vec_neu.xy())) {
|
||||
return false;
|
||||
}
|
||||
vec_neu.x = vec_ne.x;
|
||||
vec_neu.y = vec_ne.y;
|
||||
|
||||
// convert altitude
|
||||
int32_t alt_above_origin_cm = 0;
|
||||
|
|
Loading…
Reference in New Issue