diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index e7b03f61bc..dd227d7819 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -1,5 +1,4 @@ #include -#include #include "AC_WPNav.h" extern const AP_HAL::HAL& hal; @@ -1273,17 +1272,6 @@ bool AC_WPNav::get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &te /// shared methods /// -// get_bearing_cd - return bearing in centi-degrees between two positions -// To-Do: move this to math library -float AC_WPNav::get_bearing_cd(const Vector3f &origin, const Vector3f &destination) const -{ - float bearing = 9000 + atan2f(-(destination.x-origin.x), destination.y-origin.y) * DEGX100; - if (bearing < 0) { - bearing += 36000; - } - return bearing; -} - /// calc_slow_down_distance - calculates distance before waypoint that target point should begin to slow-down assuming it is travelling at full speed void AC_WPNav::calc_slow_down_distance(float speed_cms, float accel_cmss) { diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index e8abe42c7f..d72c765721 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -197,9 +197,6 @@ public: /// calculate_wp_leash_length - calculates track speed, acceleration and leash lengths for waypoint controller void calculate_wp_leash_length(); - /// get_bearing_cd - return bearing in centi-degrees between two positions - float get_bearing_cd(const Vector3f &origin, const Vector3f &destination) const; - /// /// spline methods ///