mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_InertialNav: use vector.xy().length() instead of norm(x,y)
This commit is contained in:
parent
06251335da
commit
f76f86c207
@ -81,7 +81,7 @@ const Vector3f &AP_InertialNav_NavEKF::get_velocity() const
|
|||||||
*/
|
*/
|
||||||
float AP_InertialNav_NavEKF::get_speed_xy() const
|
float AP_InertialNav_NavEKF::get_speed_xy() const
|
||||||
{
|
{
|
||||||
return norm(_velocity_cm.x, _velocity_cm.y);
|
return _velocity_cm.xy().length();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
Loading…
Reference in New Issue
Block a user