InertialNav: replace safe_sqrt with pythagorous2

This commit is contained in:
Randy Mackay 2014-04-01 20:41:26 +09:00
parent 90e205c905
commit 2ddc414f4d
1 changed files with 1 additions and 1 deletions

View File

@ -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);
}
//