mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_AHRS: use baro singleton
This commit is contained in:
parent
02205a0cb3
commit
024b29858d
@ -53,7 +53,7 @@ public:
|
||||
friend class AP_AHRS_View;
|
||||
|
||||
// Constructor
|
||||
AP_AHRS(AP_InertialSensor &ins, AP_Baro &baro) :
|
||||
AP_AHRS(AP_InertialSensor &ins) :
|
||||
roll(0.0f),
|
||||
pitch(0.0f),
|
||||
yaw(0.0f),
|
||||
@ -67,7 +67,6 @@ public:
|
||||
_beacon(nullptr),
|
||||
_compass_last_update(0),
|
||||
_ins(ins),
|
||||
_baro(baro),
|
||||
_cos_roll(1.0f),
|
||||
_cos_pitch(1.0f),
|
||||
_cos_yaw(1.0f),
|
||||
@ -211,10 +210,6 @@ public:
|
||||
return _ins;
|
||||
}
|
||||
|
||||
const AP_Baro &get_baro() const {
|
||||
return _baro;
|
||||
}
|
||||
|
||||
// get the index of the current primary accelerometer sensor
|
||||
virtual uint8_t get_primary_accel_index(void) const {
|
||||
return _ins.get_primary_accel();
|
||||
@ -639,7 +634,6 @@ 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;
|
||||
|
||||
// a vector to capture the difference between the controller and body frames
|
||||
AP_Vector3f _trim;
|
||||
|
@ -956,7 +956,7 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const
|
||||
{
|
||||
loc.lat = _last_lat;
|
||||
loc.lng = _last_lng;
|
||||
loc.alt = _baro.get_altitude() * 100 + _home.alt;
|
||||
loc.alt = AP::baro().get_altitude() * 100 + _home.alt;
|
||||
loc.flags.relative_alt = 0;
|
||||
loc.flags.terrain_alt = 0;
|
||||
location_offset(loc, _position_offset_north, _position_offset_east);
|
||||
@ -1010,7 +1010,7 @@ void AP_AHRS_DCM::set_home(const Location &loc)
|
||||
// a relative ground position to home in meters, Down
|
||||
void AP_AHRS_DCM::get_relative_position_D_home(float &posD) const
|
||||
{
|
||||
posD = -_baro.get_altitude();
|
||||
posD = -AP::baro().get_altitude();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -23,8 +23,8 @@
|
||||
|
||||
class AP_AHRS_DCM : public AP_AHRS {
|
||||
public:
|
||||
AP_AHRS_DCM(AP_InertialSensor &ins, AP_Baro &baro)
|
||||
: AP_AHRS(ins, baro)
|
||||
AP_AHRS_DCM(AP_InertialSensor &ins)
|
||||
: AP_AHRS(ins)
|
||||
, _omega_I_sum_time(0.0f)
|
||||
, _renorm_val_sum(0.0f)
|
||||
, _renorm_val_count(0)
|
||||
|
@ -31,11 +31,10 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
AP_AHRS_NavEKF::AP_AHRS_NavEKF(AP_InertialSensor &ins,
|
||||
AP_Baro &baro,
|
||||
NavEKF2 &_EKF2,
|
||||
NavEKF3 &_EKF3,
|
||||
Flags flags) :
|
||||
AP_AHRS_DCM(ins, baro),
|
||||
AP_AHRS_DCM(ins),
|
||||
EKF2(_EKF2),
|
||||
EKF3(_EKF3),
|
||||
_ekf2_started(false),
|
||||
@ -903,7 +902,7 @@ void AP_AHRS_NavEKF::get_relative_position_D_home(float &posD) const
|
||||
float originD;
|
||||
if (!get_relative_position_D_origin(originD) ||
|
||||
!get_origin(originLLH)) {
|
||||
posD = -_baro.get_altitude();
|
||||
posD = -AP::baro().get_altitude();
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -44,7 +44,7 @@ public:
|
||||
};
|
||||
|
||||
// Constructor
|
||||
AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro,
|
||||
AP_AHRS_NavEKF(AP_InertialSensor &ins,
|
||||
NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags = FLAG_NONE);
|
||||
|
||||
/* Do not allow copies */
|
||||
|
@ -26,9 +26,9 @@ static AP_SerialManager serial_manager;
|
||||
class DummyVehicle {
|
||||
public:
|
||||
RangeFinder sonar{serial_manager, ROTATION_PITCH_270};
|
||||
NavEKF2 EKF2{&ahrs, barometer, sonar};
|
||||
NavEKF3 EKF3{&ahrs, barometer, sonar};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, EKF2, EKF3,
|
||||
NavEKF2 EKF2{&ahrs, sonar};
|
||||
NavEKF3 EKF3{&ahrs, sonar};
|
||||
AP_AHRS_NavEKF ahrs{ins, EKF2, EKF3,
|
||||
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user