mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: coverity scan - variables not initialized in constructor
This commit is contained in:
parent
93462d0fe3
commit
8d2872d3ab
|
@ -80,15 +80,7 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
|
||||||
/*
|
/*
|
||||||
AP_Baro constructor
|
AP_Baro constructor
|
||||||
*/
|
*/
|
||||||
AP_Baro::AP_Baro() :
|
AP_Baro::AP_Baro()
|
||||||
_num_drivers(0),
|
|
||||||
_num_sensors(0),
|
|
||||||
_primary(0),
|
|
||||||
_last_altitude_EAS2TAS(0.0f),
|
|
||||||
_EAS2TAS(0.0f),
|
|
||||||
_external_temperature(0.0f),
|
|
||||||
_last_external_temperature_ms(0),
|
|
||||||
_hil_mode(false)
|
|
||||||
{
|
{
|
||||||
memset(sensors, 0, sizeof(sensors));
|
memset(sensors, 0, sizeof(sensors));
|
||||||
|
|
||||||
|
|
|
@ -138,14 +138,14 @@ public:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// how many drivers do we have?
|
// how many drivers do we have?
|
||||||
uint8_t _num_drivers;
|
uint8_t _num_drivers = 0;
|
||||||
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
|
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
|
||||||
|
|
||||||
// how many sensors do we have?
|
// how many sensors do we have?
|
||||||
uint8_t _num_sensors;
|
uint8_t _num_sensors = 0;
|
||||||
|
|
||||||
// what is the primary sensor at the moment?
|
// what is the primary sensor at the moment?
|
||||||
uint8_t _primary;
|
uint8_t _primary = 0;
|
||||||
|
|
||||||
struct sensor {
|
struct sensor {
|
||||||
uint32_t last_update_ms; // last update time in ms
|
uint32_t last_update_ms; // last update time in ms
|
||||||
|
@ -160,17 +160,17 @@ private:
|
||||||
} sensors[BARO_MAX_INSTANCES];
|
} sensors[BARO_MAX_INSTANCES];
|
||||||
|
|
||||||
AP_Float _alt_offset;
|
AP_Float _alt_offset;
|
||||||
float _alt_offset_active;
|
float _alt_offset_active = 0;
|
||||||
AP_Int8 _primary_baro; // primary chosen by user
|
AP_Int8 _primary_baro; // primary chosen by user
|
||||||
float _last_altitude_EAS2TAS;
|
float _last_altitude_EAS2TAS = 0;
|
||||||
float _EAS2TAS;
|
float _EAS2TAS = 0;
|
||||||
float _external_temperature;
|
float _external_temperature = 0;
|
||||||
uint32_t _last_external_temperature_ms;
|
uint32_t _last_external_temperature_ms = 0;
|
||||||
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
||||||
bool _hil_mode:1;
|
bool _hil_mode = false;
|
||||||
|
|
||||||
// when did we last notify the GCS of new pressure reference?
|
// when did we last notify the GCS of new pressure reference?
|
||||||
uint32_t _last_notify_ms;
|
uint32_t _last_notify_ms = 0;
|
||||||
|
|
||||||
void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
|
void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue