Browse Source

Change roll, pitch, yaw to be public verus private/accessors per Jason's request.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@945 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
deweibel 15 years ago
parent
commit
607b86c9a2
  1. 66
      libraries/AP_DCM/AP_DCM_FW.cpp
  2. 16
      libraries/AP_DCM/AP_DCM_FW.h

66
libraries/AP_DCM/AP_DCM_FW.cpp

@ -13,12 +13,9 @@
quick_init() : For air restart quick_init() : For air restart
init() : For ground start. Calibrates the IMU init() : For ground start. Calibrates the IMU
update_DCM(_G_Dt) : Updates the AHRS by integrating the rotation matrix over time _G_Dt using the IMU object data update_DCM(_G_Dt) : Updates the AHRS by integrating the rotation matrix over time _G_Dt using the IMU object data
get_roll_sensor() : Returns roll in degrees * 100 get_gyros() : Returns gyro vector corrected for bias
get_roll() : Returns roll in radians get_accels() : Returns accelerometer vector
get_pitch_sensor() : Returns pitch in degrees * 100 get_dcm_matrix() : Returns dcm matrix
get_pitch() : Returns pitch in radians
get_yaw_sensor() : Returns yaw in degrees * 100
get_yaw() : Returns yaw in radians
*/ */
#include <AP_DCM_FW.h> #include <AP_DCM_FW.h>
@ -102,40 +99,6 @@ AP_DCM_FW::init(uint16_t *_offset_address)
} }
/**************************************************/
long
AP_DCM_FW::get_roll_sensor(void)
{ return degrees(_roll) * 100;}
/**************************************************/
long
AP_DCM_FW::get_pitch_sensor(void)
{ return degrees(_pitch) * 100;}
/**************************************************/
long
AP_DCM_FW::get_yaw_sensor(void)
{
long yaw_sensor = degrees(_yaw) * 100;
if (yaw_sensor < 0) yaw_sensor += 36000;
return yaw_sensor;
}
/**************************************************/
float
AP_DCM_FW::get_roll(void)
{ return _roll;}
/**************************************************/
float
AP_DCM_FW::get_pitch(void)
{ return _pitch;}
/**************************************************/
float
AP_DCM_FW::get_yaw(void)
{ return _yaw;}
/**************************************************/ /**************************************************/
Vector3f Vector3f
AP_DCM_FW::get_gyros(void) AP_DCM_FW::get_gyros(void)
@ -352,9 +315,9 @@ AP_DCM_FW::drift_correction(void)
float cos_psi_err, sin_psi_err; float cos_psi_err, sin_psi_err;
// This is the case for when we first start moving and reset the DCM so that yaw matches the gps ground course // This is the case for when we first start moving and reset the DCM so that yaw matches the gps ground course
// This is just to get a reasonable estimate faster // This is just to get a reasonable estimate faster
_yaw = atan2(_dcm_matrix.b.x, _dcm_matrix.a.x); yaw = atan2(_dcm_matrix.b.x, _dcm_matrix.a.x);
cos_psi_err = cos(ToRad(_gps->ground_course/100.0) - _yaw); cos_psi_err = cos(ToRad(_gps->ground_course/100.0) - yaw);
sin_psi_err = sin(ToRad(_gps->ground_course/100.0) - _yaw); sin_psi_err = sin(ToRad(_gps->ground_course/100.0) - yaw);
// Rxx = cos psi err, Rxy = - sin psi err, Rxz = 0 // Rxx = cos psi err, Rxy = - sin psi err, Rxz = 0
// Ryx = sin psi err, Ryy = cos psi err, Ryz = 0 // Ryx = sin psi err, Ryy = cos psi err, Ryz = 0
// Rzx = Rzy = 0, Rzz = 1 // Rzx = Rzy = 0, Rzz = 1
@ -398,14 +361,19 @@ void
AP_DCM_FW::euler_angles(void) AP_DCM_FW::euler_angles(void)
{ {
#if (OUTPUTMODE == 2) // Only accelerometer info (debugging purposes) #if (OUTPUTMODE == 2) // Only accelerometer info (debugging purposes)
_roll = atan2(_accel_vector.y, -_accel_vector.z); // atan2(acc_y, acc_z) roll = atan2(_accel_vector.y, -_accel_vector.z); // atan2(acc_y, acc_z)
_pitch = asin((_accel_vector.x) / (double)9.81); // asin(acc_x) pitch = asin((_accel_vector.x) / (double)9.81); // asin(acc_x)
_yaw = 0; yaw = 0;
#else #else
_pitch = -asin(_dcm_matrix.c.x); pitch = -asin(_dcm_matrix.c.x);
_roll = atan2(_dcm_matrix.c.y, _dcm_matrix.c.z); roll = atan2(_dcm_matrix.c.y, _dcm_matrix.c.z);
_yaw = atan2(_dcm_matrix.b.x, _dcm_matrix.a.x); yaw = atan2(_dcm_matrix.b.x, _dcm_matrix.a.x);
#endif #endif
roll_sensor = degrees(roll) * 100;
pitch_sensor = degrees(pitch) * 100;
yaw_sensor = degrees(yaw) * 100;
if (yaw_sensor < 0) yaw_sensor += 36000;
} }

16
libraries/AP_DCM/AP_DCM_FW.h

@ -19,12 +19,6 @@ public:
AP_DCM_FW(GPS *GPS, APM_Compass_Class *withCompass); // Constructor for case with magnetometer AP_DCM_FW(GPS *GPS, APM_Compass_Class *withCompass); // Constructor for case with magnetometer
// Accessors // Accessors
long get_roll_sensor(void); // Degrees * 100
long get_pitch_sensor(void); // Degrees * 100
long get_yaw_sensor(void); // Degrees * 100
float get_roll(void); // Radians
float get_pitch(void); // Radians
float get_yaw(void); // Radians
Vector3f get_gyros(void); Vector3f get_gyros(void);
Vector3f get_accels(void); Vector3f get_accels(void);
Matrix3f get_dcm_matrix(void); Matrix3f get_dcm_matrix(void);
@ -36,6 +30,12 @@ public:
void init(uint16_t *_offset_address); void init(uint16_t *_offset_address);
void update_DCM(float _G_Dt); void update_DCM(float _G_Dt);
long roll_sensor; // Degrees * 100
long pitch_sensor; // Degrees * 100
long yaw_sensor; // Degrees * 100
float roll; // Radians
float pitch; // Radians
float yaw; // Radians
float imu_health; //Metric based on accel gain deweighting float imu_health; //Metric based on accel gain deweighting
uint8_t gyro_sat_count; uint8_t gyro_sat_count;
uint8_t adc_constraints; uint8_t adc_constraints;
@ -58,10 +58,6 @@ private:
GPS *_gps; GPS *_gps;
AP_IMU _imu; AP_IMU _imu;
float _roll; // radians
float _pitch; // radians
float _yaw; // radians
Matrix3f _dcm_matrix; Matrix3f _dcm_matrix;
Vector3f _accel_vector; // Store the acceleration in a vector Vector3f _accel_vector; // Store the acceleration in a vector

Loading…
Cancel
Save