mirror of https://github.com/ArduPilot/ardupilot
InertialNav: replace safe_sqrt with pythagorous2
This commit is contained in:
parent
90e205c905
commit
2ddc414f4d
|
@ -283,7 +283,7 @@ void AP_InertialNav::set_velocity_xy(float x, float y)
|
|||
// set_velocity_xy - set velocity in latitude & longitude directions (in cm/s)
|
||||
float AP_InertialNav::get_velocity_xy()
|
||||
{
|
||||
return safe_sqrt(_velocity.x * _velocity.x + _velocity.y * _velocity.y);
|
||||
return pythagorous2(_velocity.x, _velocity.y);
|
||||
}
|
||||
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue