From 76e20150e9585995b76dac45fadd0f6003619994 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Apr 2013 14:30:35 +1000 Subject: [PATCH] AP_InertialSensor: ensure parent class is initialised in instance classes --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 5 ++++- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp | 3 ++- libraries/AP_InertialSensor/AP_InertialSensor_PX4.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp | 4 ++-- 5 files changed, 10 insertions(+), 6 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 74de8ed0c4..39147bb8a2 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -92,7 +92,10 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = { AP_GROUPEND }; -AP_InertialSensor::AP_InertialSensor() { +AP_InertialSensor::AP_InertialSensor() : + _accel(), + _gyro() +{ AP_Param::setup_object_defaults(this, var_info); } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 09669b830c..0e3411c091 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -215,7 +215,7 @@ AP_HAL::Semaphore* AP_InertialSensor_MPU6000::_spi_sem = NULL; * variants however */ -AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000() +AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000() : AP_InertialSensor() { _temp = 0; _initialised = false; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp index 1749ec1257..12cf9f5209 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp @@ -38,7 +38,8 @@ const float AP_InertialSensor_Oilpan::_gyro_gain_z = ToRad(0.41f); /* ------ Public functions -------------------------------------------*/ -AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) : +AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) : + AP_InertialSensor(), _adc(adc) { } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h index 5570fcc610..26d2078c60 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h @@ -17,7 +17,7 @@ class AP_InertialSensor_PX4 : public AP_InertialSensor { public: - AP_InertialSensor_PX4() {} + AP_InertialSensor_PX4() : AP_InertialSensor() {} /* Concrete implementation of AP_InertialSensor functions: */ bool update(); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp index 1c6d3e6dca..488036a2fd 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp @@ -4,11 +4,11 @@ #include const extern AP_HAL::HAL& hal; -AP_InertialSensor_Stub::AP_InertialSensor_Stub() { +AP_InertialSensor_Stub::AP_InertialSensor_Stub() : AP_InertialSensor() { Vector3f accels; accels.z = -GRAVITY_MSS; set_accel(accels); - } +} uint16_t AP_InertialSensor_Stub::_init_sensor( Sample_rate sample_rate ) { switch (sample_rate) {