mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: Use DEGX100 define instead of hardcoded value (NFC)
This commit is contained in:
parent
ec1790dad9
commit
07c8d208bc
|
@ -144,7 +144,7 @@ void AC_Circle::update()
|
|||
_pos_control.set_xy_target(target.x, target.y);
|
||||
|
||||
// heading is 180 deg from vehicles target position around circle
|
||||
_yaw = wrap_PI(_angle-M_PI) * AC_CIRCLE_DEGX100;
|
||||
_yaw = wrap_PI(_angle-M_PI) * DEGX100;
|
||||
}else{
|
||||
// set target position to center
|
||||
Vector3f target;
|
||||
|
@ -156,7 +156,7 @@ void AC_Circle::update()
|
|||
_pos_control.set_xy_target(target.x, target.y);
|
||||
|
||||
// heading is same as _angle but converted to centi-degrees
|
||||
_yaw = _angle * AC_CIRCLE_DEGX100;
|
||||
_yaw = _angle * DEGX100;
|
||||
}
|
||||
|
||||
// update position controller
|
||||
|
|
|
@ -11,8 +11,6 @@
|
|||
#define AC_CIRCLE_RATE_DEFAULT 20.0f // turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise
|
||||
#define AC_CIRCLE_ANGULAR_ACCEL_MIN 2.0f // angular acceleration should never be less than 2deg/sec
|
||||
|
||||
#define AC_CIRCLE_DEGX100 5729.57795f // constant to convert from radians to centi-degrees
|
||||
|
||||
class AC_Circle
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -1,4 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/definitions.h>
|
||||
#include "AC_WPNav.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -1276,7 +1277,7 @@ bool AC_WPNav::get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &te
|
|||
// 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) * 5729.57795f;
|
||||
float bearing = 9000 + atan2f(-(destination.x-origin.x), destination.y-origin.y) * DEGX100;
|
||||
if (bearing < 0) {
|
||||
bearing += 36000;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue