mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_InertialSensor: ensure parent class is initialised in instance classes
This commit is contained in:
parent
a5c3051929
commit
76e20150e9
@ -92,7 +92,10 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = {
|
|||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_InertialSensor::AP_InertialSensor() {
|
AP_InertialSensor::AP_InertialSensor() :
|
||||||
|
_accel(),
|
||||||
|
_gyro()
|
||||||
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -215,7 +215,7 @@ AP_HAL::Semaphore* AP_InertialSensor_MPU6000::_spi_sem = NULL;
|
|||||||
* variants however
|
* variants however
|
||||||
*/
|
*/
|
||||||
|
|
||||||
AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000()
|
AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000() : AP_InertialSensor()
|
||||||
{
|
{
|
||||||
_temp = 0;
|
_temp = 0;
|
||||||
_initialised = false;
|
_initialised = false;
|
||||||
|
@ -38,7 +38,8 @@ const float AP_InertialSensor_Oilpan::_gyro_gain_z = ToRad(0.41f);
|
|||||||
|
|
||||||
/* ------ Public functions -------------------------------------------*/
|
/* ------ Public functions -------------------------------------------*/
|
||||||
|
|
||||||
AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) :
|
AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) :
|
||||||
|
AP_InertialSensor(),
|
||||||
_adc(adc)
|
_adc(adc)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
@ -17,7 +17,7 @@ class AP_InertialSensor_PX4 : public AP_InertialSensor
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
AP_InertialSensor_PX4() {}
|
AP_InertialSensor_PX4() : AP_InertialSensor() {}
|
||||||
|
|
||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
bool update();
|
||||||
|
@ -4,11 +4,11 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
const extern AP_HAL::HAL& hal;
|
const extern AP_HAL::HAL& hal;
|
||||||
|
|
||||||
AP_InertialSensor_Stub::AP_InertialSensor_Stub() {
|
AP_InertialSensor_Stub::AP_InertialSensor_Stub() : AP_InertialSensor() {
|
||||||
Vector3f accels;
|
Vector3f accels;
|
||||||
accels.z = -GRAVITY_MSS;
|
accels.z = -GRAVITY_MSS;
|
||||||
set_accel(accels);
|
set_accel(accels);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t AP_InertialSensor_Stub::_init_sensor( Sample_rate sample_rate ) {
|
uint16_t AP_InertialSensor_Stub::_init_sensor( Sample_rate sample_rate ) {
|
||||||
switch (sample_rate) {
|
switch (sample_rate) {
|
||||||
|
Loading…
Reference in New Issue
Block a user