Math: use common degrees() and radians() functions
This commit is contained in:
parent
7277d4934d
commit
3c0440b0b4
@ -8,8 +8,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
|
||||
|
@ -88,8 +88,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
|
@ -8,8 +8,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
|
@ -5,8 +5,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 30 // for calculating power outside of loiter radius
|
||||
|
@ -8,8 +8,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
|
@ -164,8 +164,8 @@ int SENSOR_SIGN[]={
|
||||
#define PITCH_DEF 0 // Level values for pitch, used to calculate pitch_acc_offset
|
||||
#define Z_DEF GRAVITY // Stable level value for Z, used to calculate z_acc_offset, same as GRAVITY
|
||||
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
// IDG500 Sensitivity (from datasheet) => 2.0mV/º/s, 0.8mV/ADC step => 0.8/3.33 = 0.4
|
||||
// Tested values :
|
||||
|
@ -29,8 +29,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
|
@ -29,8 +29,8 @@
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
|
@ -42,8 +42,8 @@
|
||||
|
||||
#define FPSTR(s) (wchar_t *)(s)
|
||||
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
#define ToDeg(x) degrees(x) // *180/pi
|
||||
// @}
|
||||
|
||||
|
||||
|
@ -26,7 +26,7 @@ const float AP_InertialSensor_Oilpan::_adc_constraint = 900;
|
||||
#define OILPAN_RAW_ACCEL_OFFSET ((2465.0 + 1617.0) * 0.5)
|
||||
#define OILPAN_RAW_GYRO_OFFSET 1658.0
|
||||
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToRad(x) radians(x) // *pi/180
|
||||
// IDG500 Sensitivity (from datasheet) => 2.0mV/degree/s,
|
||||
// 0.8mV/ADC step => 0.8/3.33 = 0.4
|
||||
// Tested values : 0.4026, ?, 0.4192
|
||||
|
Loading…
Reference in New Issue
Block a user