mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF2: use baro singleton
This commit is contained in:
parent
8d8f2208c0
commit
5ab89324b2
@ -555,9 +555,8 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
|
|||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
NavEKF2::NavEKF2(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
|
NavEKF2::NavEKF2(const AP_AHRS *ahrs, const RangeFinder &rng) :
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
_baro(baro),
|
|
||||||
_rng(rng)
|
_rng(rng)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
@ -580,7 +579,7 @@ void NavEKF2::check_log_write(void)
|
|||||||
logging.log_gps = false;
|
logging.log_gps = false;
|
||||||
}
|
}
|
||||||
if (logging.log_baro) {
|
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;
|
logging.log_baro = false;
|
||||||
}
|
}
|
||||||
if (logging.log_imu) {
|
if (logging.log_imu) {
|
||||||
|
@ -38,7 +38,7 @@ class NavEKF2 {
|
|||||||
friend class NavEKF2_core;
|
friend class NavEKF2_core;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
NavEKF2(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng);
|
NavEKF2(const AP_AHRS *ahrs, const RangeFinder &rng);
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
NavEKF2(const NavEKF2 &other) = delete;
|
NavEKF2(const NavEKF2 &other) = delete;
|
||||||
@ -328,7 +328,6 @@ private:
|
|||||||
uint8_t primary; // current primary core
|
uint8_t primary; // current primary core
|
||||||
NavEKF2_core *core = nullptr;
|
NavEKF2_core *core = nullptr;
|
||||||
const AP_AHRS *_ahrs;
|
const AP_AHRS *_ahrs;
|
||||||
AP_Baro &_baro;
|
|
||||||
const RangeFinder &_rng;
|
const RangeFinder &_rng;
|
||||||
|
|
||||||
uint32_t _frameTimeUsec; // time per IMU frame
|
uint32_t _frameTimeUsec; // time per IMU frame
|
||||||
|
@ -556,10 +556,11 @@ void NavEKF2_core::readBaroData()
|
|||||||
{
|
{
|
||||||
// check to see if baro measurement has changed so we know if a new measurement has arrived
|
// check to see if baro measurement has changed so we know if a new measurement has arrived
|
||||||
// do not accept data at a faster rate than 14Hz to avoid overflowing the FIFO buffer
|
// do not accept data at a faster rate than 14Hz to avoid overflowing the FIFO buffer
|
||||||
if (frontend->_baro.get_last_update() - lastBaroReceived_ms > 70) {
|
const AP_Baro &baro = AP::baro();
|
||||||
|
if (baro.get_last_update() - lastBaroReceived_ms > 70) {
|
||||||
frontend->logging.log_baro = true;
|
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
|
// 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
|
// This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
|
||||||
@ -568,7 +569,7 @@ void NavEKF2_core::readBaroData()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// time stamp used to check for new measurement
|
// 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
|
// estimate of time height measurement was taken, allowing for delays
|
||||||
baroDataNew.time_ms = lastBaroReceived_ms - frontend->_hgtDelay_ms;
|
baroDataNew.time_ms = lastBaroReceived_ms - frontend->_hgtDelay_ms;
|
||||||
|
@ -204,7 +204,7 @@ bool NavEKF2_core::resetHeightDatum(void)
|
|||||||
// record the old height estimate
|
// record the old height estimate
|
||||||
float oldHgt = -stateStruct.position.z;
|
float oldHgt = -stateStruct.position.z;
|
||||||
// reset the barometer so that it reads zero at the current height
|
// reset the barometer so that it reads zero at the current height
|
||||||
frontend->_baro.update_calibration();
|
AP::baro().update_calibration();
|
||||||
// reset the height state
|
// reset the height state
|
||||||
stateStruct.position.z = 0.0f;
|
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
|
// adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
|
||||||
|
Loading…
Reference in New Issue
Block a user