diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index e458fe2438..de4c850017 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -37,7 +37,7 @@ class AP_AHRS { public: // Constructor - AP_AHRS(AP_InertialSensor *ins, GPS *&gps) : + AP_AHRS(AP_InertialSensor &ins, GPS *&gps) : _ins(ins), _gps(gps) { @@ -49,7 +49,7 @@ public: // prone than the APM1, so we should have a lower ki, // which will make us less prone to increasing omegaI // incorrectly due to sensor noise - _gyro_drift_limit = ins->get_gyro_drift_rate(); + _gyro_drift_limit = ins.get_gyro_drift_rate(); // enable centrifugal correction by default _flags.correct_centrifugal = true; @@ -78,7 +78,7 @@ public: // allow for runtime change of orientation // this makes initial config easier void set_orientation() { - _ins->set_board_orientation((enum Rotation)_board_orientation.get()); + _ins.set_board_orientation((enum Rotation)_board_orientation.get()); if (_compass != NULL) { _compass->set_board_orientation((enum Rotation)_board_orientation.get()); } @@ -88,7 +88,7 @@ public: _airspeed = airspeed; } - AP_InertialSensor* get_ins() const { + const AP_InertialSensor &get_ins() const { return _ins; } @@ -263,7 +263,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_InertialSensor &_ins; GPS *&_gps; // a vector to capture the difference between the controller and body frames diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index a212deb126..5a950b0315 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -48,10 +48,10 @@ AP_AHRS_DCM::update(void) float delta_t; // tell the IMU to grab some data - _ins->update(); + _ins.update(); // ask the IMU how much time this sensor reading represents - delta_t = _ins->get_delta_time(); + delta_t = _ins.get_delta_time(); // if the update call took more than 0.2 seconds then discard it, // otherwise we may move too far. This happens when arming motors @@ -62,10 +62,6 @@ AP_AHRS_DCM::update(void) return; } - // Get current values for gyros - _gyro_vector = _ins->get_gyro(); - _accel_vector = _ins->get_accel(); - // Integrate the DCM matrix using gyro inputs matrix_update(delta_t); @@ -91,7 +87,7 @@ AP_AHRS_DCM::matrix_update(float _G_Dt) // and including the P terms would give positive feedback into // the _P_gain() calculation, which can lead to a very large P // value - _omega = _gyro_vector + _omega_I; + _omega = _ins.get_gyro() + _omega_I; _dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * _G_Dt); } @@ -461,7 +457,7 @@ AP_AHRS_DCM::drift_correction(float deltat) temp_dcm.rotateXY(_trim); // rotate accelerometer values into the earth frame - _accel_ef = temp_dcm * _accel_vector; + _accel_ef = temp_dcm * _ins.get_accel(); // integrate the accel vector in the earth frame between GPS readings _ra_sum += _accel_ef * deltat; @@ -625,7 +621,7 @@ AP_AHRS_DCM::drift_correction(float deltat) if (_flags.fly_forward && _gps && _gps->status() >= GPS::GPS_OK_FIX_2D && _gps->ground_speed_cm < GPS_SPEED_MIN && - _accel_vector.x >= 7 && + _ins.get_accel().x >= 7 && pitch_sensor > -3000 && pitch_sensor < 3000) { // assume we are in a launch acceleration, and reduce the // rp gain by 50% to reduce the impact of GPS lag on diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 4884cbe74a..4b4340108a 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -25,7 +25,7 @@ class AP_AHRS_DCM : public AP_AHRS { public: // Constructors - AP_AHRS_DCM(AP_InertialSensor *ins, GPS *&gps) : + AP_AHRS_DCM(AP_InertialSensor &ins, GPS *&gps) : AP_AHRS(ins, gps), _last_declination(0), _mag_earth(1,0) @@ -92,9 +92,6 @@ private: // primary representation of attitude Matrix3f _dcm_matrix; - Vector3f _gyro_vector; // Store the gyros turn rate in a vector - Vector3f _accel_vector; // current accel vector - Vector3f _omega_P; // accel Omega proportional correction Vector3f _omega_yaw_P; // proportional yaw correction Vector3f _omega_I; // Omega Integrator correction diff --git a/libraries/AP_AHRS/AP_AHRS_HIL.h b/libraries/AP_AHRS/AP_AHRS_HIL.h index b4bc56f51b..7081114510 100644 --- a/libraries/AP_AHRS/AP_AHRS_HIL.h +++ b/libraries/AP_AHRS/AP_AHRS_HIL.h @@ -5,7 +5,7 @@ class AP_AHRS_HIL : public AP_AHRS { public: // Constructors - AP_AHRS_HIL(AP_InertialSensor *ins, GPS *&gps) : + AP_AHRS_HIL(AP_InertialSensor &ins, GPS *&gps) : AP_AHRS(ins, gps), _drift() {} @@ -21,7 +21,7 @@ public: // Methods void update(void) { - _ins->update(); + _ins.update(); } void setHil(float roll, float pitch, float yaw, diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.pde b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.pde index f77889a268..07712923cd 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.pde +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.pde @@ -48,7 +48,7 @@ GPS *g_gps; AP_GPS_Auto g_gps_driver(&g_gps); // choose which AHRS system to use -AP_AHRS_DCM ahrs(&ins, g_gps); +AP_AHRS_DCM ahrs(ins, g_gps); AP_Baro_HIL barometer;