mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
InertialNav: fix for get_velocity_xy
forgot to sq
This commit is contained in:
parent
9951c50e48
commit
1c7d9f43c1
@ -279,7 +279,7 @@ void AP_InertialNav::set_velocity_xy(float x, float y)
|
|||||||
// set_velocity_xy - set velocity in latitude & longitude directions (in cm/s)
|
// set_velocity_xy - set velocity in latitude & longitude directions (in cm/s)
|
||||||
float AP_InertialNav::get_velocity_xy()
|
float AP_InertialNav::get_velocity_xy()
|
||||||
{
|
{
|
||||||
return safe_sqrt(_velocity.x + _velocity.y);
|
return safe_sqrt(_velocity.x * _velocity.x + _velocity.y * _velocity.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user