mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Baro: MS56XX: remove initialization to 0 from constructor
This commit is contained in:
parent
5bb2716081
commit
56e4de0bdd
@ -167,15 +167,10 @@ void AP_SerialBus_I2C::sem_give()
|
||||
/*
|
||||
constructor
|
||||
*/
|
||||
AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer) :
|
||||
AP_Baro_Backend(baro),
|
||||
_serial(serial),
|
||||
_updated(false),
|
||||
_state(0),
|
||||
_last_timer(0),
|
||||
_use_timer(use_timer),
|
||||
_D1(0.0f),
|
||||
_D2(0.0f)
|
||||
AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer)
|
||||
: AP_Baro_Backend(baro)
|
||||
, _serial(serial)
|
||||
, _use_timer(use_timer)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -100,7 +100,7 @@ protected:
|
||||
|
||||
// Internal calibration registers
|
||||
uint16_t _c1,_c2,_c3,_c4,_c5,_c6;
|
||||
float _D1,_D2;
|
||||
float _D1, _D2;
|
||||
uint8_t _instance;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user