From 4c1de1abf37360ffd7657470aee8c173958148b5 Mon Sep 17 00:00:00 2001 From: Grant Morphett Date: Wed, 29 Jul 2015 17:23:30 +1000 Subject: [PATCH] AP_InertialSensor: fix coverity warnings - param init in construct --- .../AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 45197f1a24..00691c4436 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -176,7 +176,8 @@ extern const AP_HAL::HAL& hal; /* SPI bus driver implementation */ -AP_MPU6000_BusDriver_SPI::AP_MPU6000_BusDriver_SPI(void) +AP_MPU6000_BusDriver_SPI::AP_MPU6000_BusDriver_SPI(void) : + _error_count(0) { _spi = hal.spi->device(AP_HAL::SPIDevice_MPU6000); } @@ -273,7 +274,8 @@ AP_HAL::Semaphore* AP_MPU6000_BusDriver_SPI::get_semaphore() /* I2C bus driver implementation */ AP_MPU6000_BusDriver_I2C::AP_MPU6000_BusDriver_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr) : _addr(addr), - _i2c(i2c) + _i2c(i2c), + _i2c_sem(NULL) {} void AP_MPU6000_BusDriver_I2C::init(bool &fifo_mode, uint8_t &max_samples) @@ -392,7 +394,8 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000(AP_InertialSensor &imu, AP_ _accel_sum(), _gyro_sum(), #endif - _sum_count(0) + _sum_count(0), + _samples(NULL) { }