Updated DCM library.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@996 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
45ddbbf982
commit
110685f880
@ -262,7 +262,7 @@ AP_DCM::drift_correction(void)
|
||||
|
||||
if (_compass) {
|
||||
// We make the gyro YAW drift correction based on compass magnetic heading
|
||||
error_course= (_dcm_matrix.a.x * _compass->Heading_Y) - (_dcm_matrix.b.x * _compass->Heading_X); // Equation 23, Calculating YAW error
|
||||
error_course= (_dcm_matrix.a.x * _compass->headingY) - (_dcm_matrix.b.x * _compass->headingX); // Equation 23, Calculating YAW error
|
||||
} else {
|
||||
// Use GPS Ground course to correct yaw gyro drift
|
||||
if (_gps->ground_speed >= SPEEDFILT) {
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include <AP_Math.h>
|
||||
#include <inttypes.h>
|
||||
#include "WProgram.h"
|
||||
#include <APM_Compass.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_IMU.h>
|
||||
@ -26,7 +26,7 @@ public:
|
||||
_course_over_ground_y(1)
|
||||
{}
|
||||
|
||||
AP_DCM(AP_IMU *imu, GPS *gps, APM_Compass_Class *withCompass) :
|
||||
AP_DCM(AP_IMU *imu, GPS *gps, Compass *withCompass) :
|
||||
_imu(imu),
|
||||
_gps(gps),
|
||||
_compass(withCompass),
|
||||
@ -73,7 +73,7 @@ private:
|
||||
void euler_angles(void);
|
||||
|
||||
// members
|
||||
APM_Compass_Class * _compass;
|
||||
Compass * _compass;
|
||||
GPS * _gps;
|
||||
AP_IMU * _imu;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user