mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: use Vector3f.xy() to avoid creating a fresh Vector2f
This commit is contained in:
parent
70c2775949
commit
141074d07a
|
@ -1257,13 +1257,13 @@ Vector2f AP_AHRS::groundspeed_vector(void)
|
||||||
#if HAL_NAVEKF2_AVAILABLE
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
case EKFType::TWO:
|
case EKFType::TWO:
|
||||||
EKF2.getVelNED(vec);
|
EKF2.getVelNED(vec);
|
||||||
return Vector2f(vec.x, vec.y);
|
return vec.xy();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAL_NAVEKF3_AVAILABLE
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
case EKFType::THREE:
|
case EKFType::THREE:
|
||||||
EKF3.getVelNED(vec);
|
EKF3.getVelNED(vec);
|
||||||
return Vector2f(vec.x, vec.y);
|
return vec.xy();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_AHRS_SIM_ENABLED
|
#if AP_AHRS_SIM_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue