From 7fd285f483af80fcb34bed865b1eb9556bff6e42 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 4 May 2015 15:42:05 -0700 Subject: [PATCH] AC_WPNav: 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 https://github.com/Airphrame/ardupilot/commit/ccd578664ffdb5998d2655bd020ae48e7ea628de#commitcomment-11025083 --- libraries/AC_WPNav/AC_Circle.cpp | 2 +- libraries/AC_WPNav/AC_WPNav.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index f3bada27c8..c537895f61 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -247,7 +247,7 @@ void AC_Circle::init_start_angle(bool use_heading) _angle = wrap_PI(_ahrs.yaw-PI); } else { // get bearing from circle center to vehicle in radians - float bearing_rad = fast_atan2(curr_pos.y-_center.y,curr_pos.x-_center.x); + float bearing_rad = atan2f(curr_pos.y-_center.y,curr_pos.x-_center.x); _angle = wrap_PI(bearing_rad); } } diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 8ae35213f3..0d7b812aa4 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -962,7 +962,7 @@ void AC_WPNav::advance_spline_target_along_track(float dt) _pos_control.set_pos_target(target_pos); // update the yaw - _yaw = RadiansToCentiDegrees(fast_atan2(target_vel.y,target_vel.x)); + _yaw = RadiansToCentiDegrees(atan2f(target_vel.y,target_vel.x)); // advance spline time to next step _spline_time += _spline_time_scale*dt; @@ -1001,7 +1001,7 @@ void AC_WPNav::calc_spline_pos_vel(float spline_time, Vector3f& position, Vector // To-Do: move this to math library float AC_WPNav::get_bearing_cd(const Vector3f &origin, const Vector3f &destination) const { - float bearing = 9000 + fast_atan2(-(destination.x-origin.x), destination.y-origin.y) * 5729.57795f; + float bearing = 9000 + atan2f(-(destination.x-origin.x), destination.y-origin.y) * 5729.57795f; if (bearing < 0) { bearing += 36000; }