mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Return product ID from sensor initialization
this exposes the product ID to the IMU Layer
This commit is contained in:
parent
a22b15adf1
commit
c323a71933
|
@ -13,7 +13,7 @@ class AP_InertialSensor
|
|||
public:
|
||||
AP_InertialSensor() {}
|
||||
|
||||
virtual void init( AP_PeriodicProcess * scheduler ) = 0;
|
||||
virtual uint16_t init( AP_PeriodicProcess * scheduler ) = 0;
|
||||
|
||||
/* Update the sensor data, so that getters are nonblocking.
|
||||
* Returns a bool of whether data was updated or not.
|
||||
|
|
|
@ -119,14 +119,15 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000( uint8_t cs_pin )
|
|||
_initialised = 0;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler )
|
||||
uint16_t AP_InertialSensor_MPU6000::init( AP_PeriodicProcess * scheduler )
|
||||
{
|
||||
if (_initialised) return;
|
||||
if (_initialised) return _product_id;
|
||||
_initialised = 1;
|
||||
scheduler->suspend_timer();
|
||||
hardware_init();
|
||||
scheduler->resume_timer();
|
||||
scheduler->register_process( &AP_InertialSensor_MPU6000::read );
|
||||
return _product_id;
|
||||
}
|
||||
|
||||
// accumulation in ISR - must be read with interrupts disabled
|
||||
|
|
|
@ -16,7 +16,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
|
|||
|
||||
AP_InertialSensor_MPU6000( uint8_t cs_pin );
|
||||
|
||||
void init( AP_PeriodicProcess * scheduler );
|
||||
uint16_t init( AP_PeriodicProcess * scheduler );
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
||||
|
|
|
@ -48,9 +48,17 @@ AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) :
|
|||
_accel.z = 0;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_Oilpan::init( AP_PeriodicProcess * scheduler)
|
||||
uint16_t AP_InertialSensor_Oilpan::init( AP_PeriodicProcess * scheduler)
|
||||
{
|
||||
_adc->Init(scheduler);
|
||||
|
||||
#if defined(DESKTOP_BUILD)
|
||||
return AP_PRODUCT_ID_SITL;
|
||||
#elif defined(__AVR_ATmega1280__)
|
||||
return AP_PRODUCT_ID_APM1_1280;
|
||||
#else
|
||||
return AP_PRODUCT_ID_APM1_2560;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_Oilpan::update()
|
||||
|
|
|
@ -17,7 +17,7 @@ class AP_InertialSensor_Oilpan : public AP_InertialSensor
|
|||
AP_InertialSensor_Oilpan( AP_ADC * adc );
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
void init(AP_PeriodicProcess * scheduler);
|
||||
uint16_t init(AP_PeriodicProcess * scheduler);
|
||||
bool update();
|
||||
bool new_data_available();
|
||||
float gx();
|
||||
|
|
|
@ -2,7 +2,9 @@
|
|||
|
||||
#include "AP_InertialSensor_Stub.h"
|
||||
|
||||
void AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {}
|
||||
uint16_t AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {
|
||||
return AP_PRODUCT_ID_NONE;
|
||||
}
|
||||
|
||||
/*================ AP_INERTIALSENSOR PUBLIC INTERFACE ==================== */
|
||||
|
||||
|
|
|
@ -15,7 +15,7 @@ class AP_InertialSensor_Stub : public AP_InertialSensor
|
|||
|
||||
AP_InertialSensor_Stub() {}
|
||||
|
||||
void init( AP_PeriodicProcess * scheduler );
|
||||
uint16_t init( AP_PeriodicProcess * scheduler );
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
||||
|
|
Loading…
Reference in New Issue