mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Baro: Move initialisation code from MS56XX constructor to init()
On MS5637 we will need to override the method to read and calculate the PROM's crc. Thus we need a 2-phase init. It also makes the constructor of AP_Baro_MS56XX protected since only the derived classes should instantiate the base one.
This commit is contained in:
parent
29791c9cec
commit
7457588d7c
@ -183,6 +183,10 @@ AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_tim
|
||||
_use_timer(use_timer),
|
||||
_D1(0.0f),
|
||||
_D2(0.0f)
|
||||
{
|
||||
}
|
||||
|
||||
void AP_Baro_MS56XX::_init()
|
||||
{
|
||||
_instance = _frontend.register_sensor();
|
||||
_serial->init();
|
||||
@ -385,8 +389,10 @@ void AP_Baro_MS56XX::update()
|
||||
|
||||
/* MS5611 class */
|
||||
AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial, bool use_timer)
|
||||
:AP_Baro_MS56XX(baro, serial, use_timer)
|
||||
{}
|
||||
: AP_Baro_MS56XX(baro, serial, use_timer)
|
||||
{
|
||||
_init();
|
||||
}
|
||||
|
||||
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
|
||||
void AP_Baro_MS5611::_calculate()
|
||||
@ -425,8 +431,11 @@ void AP_Baro_MS5611::_calculate()
|
||||
|
||||
/* MS5607 Class */
|
||||
AP_Baro_MS5607::AP_Baro_MS5607(AP_Baro &baro, AP_SerialBus *serial, bool use_timer)
|
||||
:AP_Baro_MS56XX(baro, serial, use_timer)
|
||||
{}
|
||||
: AP_Baro_MS56XX(baro, serial, use_timer)
|
||||
{
|
||||
_init();
|
||||
}
|
||||
|
||||
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
|
||||
void AP_Baro_MS5607::_calculate()
|
||||
{
|
||||
@ -466,6 +475,7 @@ void AP_Baro_MS5607::_calculate()
|
||||
AP_Baro_MS5637::AP_Baro_MS5637(AP_Baro &baro, AP_SerialBus *serial, bool use_timer)
|
||||
: AP_Baro_MS56XX(baro, serial, use_timer)
|
||||
{
|
||||
_init();
|
||||
}
|
||||
|
||||
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
|
||||
|
@ -75,12 +75,12 @@ private:
|
||||
class AP_Baro_MS56XX : public AP_Baro_Backend
|
||||
{
|
||||
public:
|
||||
AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
||||
void update();
|
||||
void accumulate();
|
||||
|
||||
private:
|
||||
virtual void _calculate() = 0;
|
||||
|
||||
AP_SerialBus *_serial;
|
||||
|
||||
bool _check_crc();
|
||||
@ -98,6 +98,9 @@ private:
|
||||
bool _use_timer;
|
||||
|
||||
protected:
|
||||
AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
||||
void _init();
|
||||
|
||||
// Internal calibration registers
|
||||
uint16_t _C1,_C2,_C3,_C4,_C5,_C6;
|
||||
float _D1,_D2;
|
||||
|
Loading…
Reference in New Issue
Block a user