AP_NavEKF3: use baro singleton

This commit is contained in:
Peter Barker 2018-03-06 07:35:51 +11:00 committed by Lucas De Marchi
parent 5ab89324b2
commit 7b1a906c4e
4 changed files with 8 additions and 9 deletions

View File

@ -579,9 +579,8 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
AP_GROUPEND
};
NavEKF3::NavEKF3(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
NavEKF3::NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng) :
_ahrs(ahrs),
_baro(baro),
_rng(rng),
gpsNEVelVarAccScale(0.05f), // Scale factor applied to horizontal velocity measurement variance due to manoeuvre acceleration - used when GPS doesn't report speed error
gpsDVelVarAccScale(0.07f), // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration - used when GPS doesn't report speed error
@ -634,7 +633,7 @@ void NavEKF3::check_log_write(void)
logging.log_gps = false;
}
if (logging.log_baro) {
DataFlash_Class::instance()->Log_Write_Baro(_baro, imuSampleTime_us);
DataFlash_Class::instance()->Log_Write_Baro(imuSampleTime_us);
logging.log_baro = false;
}
if (logging.log_imu) {

View File

@ -35,7 +35,7 @@ class NavEKF3 {
friend class NavEKF3_core;
public:
NavEKF3(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng);
NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng);
/* Do not allow copies */
NavEKF3(const NavEKF3 &other) = delete;
@ -359,7 +359,6 @@ private:
uint8_t primary; // current primary core
NavEKF3_core *core = nullptr;
const AP_AHRS *_ahrs;
AP_Baro &_baro;
const RangeFinder &_rng;
uint32_t _frameTimeUsec; // time per IMU frame

View File

@ -603,10 +603,11 @@ void NavEKF3_core::readBaroData()
{
// check to see if baro measurement has changed so we know if a new measurement has arrived
// limit update rate to avoid overflowing the FIFO buffer
if (frontend->_baro.get_last_update() - lastBaroReceived_ms > frontend->sensorIntervalMin_ms) {
const AP_Baro &baro = AP::baro();
if (baro.get_last_update() - lastBaroReceived_ms > frontend->sensorIntervalMin_ms) {
frontend->logging.log_baro = true;
baroDataNew.hgt = frontend->_baro.get_altitude();
baroDataNew.hgt = baro.get_altitude();
// If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
// This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
@ -615,7 +616,7 @@ void NavEKF3_core::readBaroData()
}
// time stamp used to check for new measurement
lastBaroReceived_ms = frontend->_baro.get_last_update();
lastBaroReceived_ms = baro.get_last_update();
// estimate of time height measurement was taken, allowing for delays
baroDataNew.time_ms = lastBaroReceived_ms - frontend->_hgtDelay_ms;

View File

@ -208,7 +208,7 @@ bool NavEKF3_core::resetHeightDatum(void)
// record the old height estimate
float oldHgt = -stateStruct.position.z;
// reset the barometer so that it reads zero at the current height
frontend->_baro.update_calibration();
AP::baro().update_calibration();
// reset the height state
stateStruct.position.z = 0.0f;
// adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same