AP_InertialNav: use references to AHRS and baro

This commit is contained in:
Andrew Tridgell 2014-01-02 16:04:52 +11:00
parent 18aa08d5c3
commit cfc612b251
2 changed files with 6 additions and 9 deletions

View File

@ -50,7 +50,7 @@ void AP_InertialNav::update(float dt)
// check if new gps readings have arrived and use them to correct position estimates
check_gps();
Vector3f accel_ef = _ahrs->get_accel_ef();
Vector3f accel_ef = _ahrs.get_accel_ef();
// remove influence of gravity
accel_ef.z += GRAVITY_MSS;
@ -310,15 +310,12 @@ void AP_InertialNav::check_baro()
{
uint32_t baro_update_time;
if( _baro == NULL )
return;
// calculate time since last baro reading (in ms)
baro_update_time = _baro->get_last_update();
baro_update_time = _baro.get_last_update();
if( baro_update_time != _baro_last_update ) {
const float dt = (float)(baro_update_time - _baro_last_update) * 0.001f; // in seconds
// call correction method
correct_with_baro(_baro->get_altitude()*100, dt);
correct_with_baro(_baro.get_altitude()*100, dt);
_baro_last_update = baro_update_time;
}
}

View File

@ -34,7 +34,7 @@ class AP_InertialNav
public:
// Constructor
AP_InertialNav( const AP_AHRS* ahrs, AP_Baro* baro, GPS*& gps, GPS_Glitch& gps_glitch ) :
AP_InertialNav( const AP_AHRS &ahrs, AP_Baro &baro, GPS*& gps, GPS_Glitch& gps_glitch ) :
_ahrs(ahrs),
_baro(baro),
_gps(gps),
@ -280,8 +280,8 @@ protected:
uint8_t ignore_error : 3; // the number of iterations for which we should ignore errors
} _flags;
const AP_AHRS* const _ahrs; // pointer to ahrs object
AP_Baro* _baro; // pointer to barometer
const AP_AHRS &_ahrs; // reference to ahrs object
AP_Baro &_baro; // reference to barometer
GPS*& _gps; // pointer to gps
// XY Axis specific variables