mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_InertialSensor_MPU6k: init members to reduce compiler warnings
This commit is contained in:
parent
c5a03ea18e
commit
a09f7b9198
@ -176,8 +176,15 @@ const float AP_InertialSensor_MPU6000::_gyro_scale = (0.0174532f / 16.4f);
|
|||||||
AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000() :
|
AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000() :
|
||||||
AP_InertialSensor(),
|
AP_InertialSensor(),
|
||||||
_drdy_pin(NULL),
|
_drdy_pin(NULL),
|
||||||
|
_spi(NULL),
|
||||||
|
_spi_sem(NULL),
|
||||||
|
_num_samples(0),
|
||||||
|
_last_sample_time_micros(0),
|
||||||
_initialised(false),
|
_initialised(false),
|
||||||
_mpu6000_product_id(AP_PRODUCT_ID_NONE)
|
_mpu6000_product_id(AP_PRODUCT_ID_NONE),
|
||||||
|
_sample_shift(0),
|
||||||
|
_last_filter_hz(0),
|
||||||
|
_error_count(0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user