Browse Source

AP_Common: Remove extra comparison from longitude_scale()

master
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
6e0cceff0d
  1. 2
      libraries/AP_Common/Location.cpp

2
libraries/AP_Common/Location.cpp

@ -271,7 +271,7 @@ void Location::offset_bearing(float bearing, float distance) @@ -271,7 +271,7 @@ void Location::offset_bearing(float bearing, float distance)
float Location::longitude_scale() const
{
float scale = cosf(lat * (1.0e-7f * DEG_TO_RAD));
return constrain_float(scale, 0.01f, 1.0f);
return MAX(scale, 0.01f);
}
/*

Loading…
Cancel
Save