From 1e476e511acc2bd06f83ec2ef319bb5a28bb41a4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 Jan 2014 17:06:30 +1100 Subject: [PATCH] AP_AHRS: pass baro into AP_AHRS first step in making AHRS handle altitude --- libraries/AP_AHRS/AP_AHRS.h | 12 +++++++++--- libraries/AP_AHRS/AP_AHRS_DCM.h | 4 ++-- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 4 ++-- 3 files changed, 13 insertions(+), 7 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 333ee7b77d..b797bcf830 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -37,16 +37,17 @@ class AP_AHRS { public: // Constructor - AP_AHRS(AP_InertialSensor &ins, GPS *&gps) : + AP_AHRS(AP_InertialSensor &ins, AP_Baro &baro, GPS *&gps) : _compass(NULL), _ins(ins), - _gps(gps), _cos_roll(1.0f), _cos_pitch(1.0f), _cos_yaw(1.0f), _sin_roll(0.0f), _sin_pitch(0.0f), - _sin_yaw(0.0f) + _sin_yaw(0.0f), + _baro(baro), + _gps(gps) { // load default values from var_info table AP_Param::setup_object_defaults(this, var_info); @@ -110,6 +111,10 @@ public: return _ins; } + const AP_Baro &get_baro() const { + return _baro; + } + // accelerometer values in the earth frame in m/s/s const Vector3f &get_accel_ef(void) const { return _accel_ef; } @@ -305,6 +310,7 @@ protected: // note: we use ref-to-pointer here so that our caller can change the GPS without our noticing // IMU under us without our noticing. AP_InertialSensor &_ins; + AP_Baro &_baro; GPS *&_gps; // a vector to capture the difference between the controller and body frames diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 9cc56ccf06..2c6cb3eb2e 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -25,8 +25,8 @@ class AP_AHRS_DCM : public AP_AHRS { public: // Constructors - AP_AHRS_DCM(AP_InertialSensor &ins, GPS *&gps) : - AP_AHRS(ins, gps), + AP_AHRS_DCM(AP_InertialSensor &ins, AP_Baro &baro, GPS *&gps) : + AP_AHRS(ins, baro, gps), _last_declination(0), _mag_earth(1,0) { diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index c682b96046..2b6565fbd2 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -32,8 +32,8 @@ class AP_AHRS_NavEKF : public AP_AHRS_DCM { public: // Constructor - AP_AHRS_NavEKF(AP_InertialSensor &ins, GPS *&gps, AP_Baro &baro) : - AP_AHRS_DCM(ins, gps), + AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, GPS *&gps) : + AP_AHRS_DCM(ins, baro, gps), EKF(this, baro), _baro(baro), ekf_started(false),