Copter: Compiler warnings: nuke fast_atan2()

per Randy's suggestion, fast_atan2() is no longer necessary over atan2() because only copter uses it and copter is no longer supported on future builds of APM

ccd578664f (commitcomment-11025083)
This commit is contained in:
Tom Pittenger 2015-05-04 15:42:19 -07:00 committed by Andrew Tridgell
parent 7fd285f483
commit 5704a5a2a7

View File

@ -52,7 +52,7 @@ float pv_alt_above_home(float alt_above_origin_cm)
// pv_get_bearing_cd - return bearing in centi-degrees between two positions
float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
{
float bearing = fast_atan2(destination.y-origin.y, destination.x-origin.x) * DEGX100;
float bearing = atan2f(destination.y-origin.y, destination.x-origin.x) * DEGX100;
if (bearing < 0) {
bearing += 36000;
}