mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: L3G4200D: add probe code
This driver works properly but had the initialization logic missing. Add the support to probe it.
This commit is contained in:
parent
55279664c2
commit
d3eebdb6aa
@ -420,6 +420,8 @@ AP_InertialSensor::_detect_backends(void)
|
||||
_add_backend(AP_InertialSensor_Flymaple::detect);
|
||||
#elif HAL_INS_DEFAULT == HAL_INS_LSM9DS0
|
||||
_add_backend(AP_InertialSensor_LSM9DS0::detect);
|
||||
#elif HAL_INS_DEFAULT == HAL_INS_L3G4200D
|
||||
_add_backend(AP_InertialSensor_L3G4200D::detect);
|
||||
#else
|
||||
#error Unrecognised HAL_INS_TYPE setting
|
||||
#endif
|
||||
|
@ -129,6 +129,23 @@ AP_InertialSensor_L3G4200D::~AP_InertialSensor_L3G4200D()
|
||||
pthread_spin_destroy(&_data_lock);
|
||||
}
|
||||
|
||||
/*
|
||||
detect the sensor
|
||||
*/
|
||||
AP_InertialSensor_Backend *AP_InertialSensor_L3G4200D::detect(AP_InertialSensor &_imu)
|
||||
{
|
||||
AP_InertialSensor_L3G4200D *sensor = new AP_InertialSensor_L3G4200D(_imu);
|
||||
if (sensor == NULL) {
|
||||
return NULL;
|
||||
}
|
||||
if (!sensor->_init_sensor()) {
|
||||
delete sensor;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
return sensor;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_L3G4200D::_init_sensor(void)
|
||||
{
|
||||
// get pointer to i2c bus semaphore
|
||||
|
Loading…
Reference in New Issue
Block a user