AP_InertialSensor: BMI160: Make it possible to use I2C

The BMI160 chip talks the same protocol over SPI and I2C,
so simply allowing I2C in hwdef is sufficient to allow it to be used.
This commit is contained in:
Scott Parlane 2021-08-11 21:51:32 +12:00 committed by Andrew Tridgell
parent 6554c535a1
commit 700edd241f
2 changed files with 26 additions and 0 deletions

View File

@ -146,6 +146,27 @@ AP_InertialSensor_BMI160::probe(AP_InertialSensor &imu,
return sensor; return sensor;
} }
AP_InertialSensor_Backend *
AP_InertialSensor_BMI160::probe(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
{
if (!dev) {
return nullptr;
}
auto sensor = new AP_InertialSensor_BMI160(imu, std::move(dev));
if (!sensor) {
return nullptr;
}
if (!sensor->_init()) {
delete sensor;
return nullptr;
}
return sensor;
}
void AP_InertialSensor_BMI160::start() void AP_InertialSensor_BMI160::start()
{ {
bool r; bool r;

View File

@ -17,6 +17,8 @@
#pragma once #pragma once
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/SPIDevice.h>
#include <AP_HAL/I2CDevice.h>
#include "AP_InertialSensor.h" #include "AP_InertialSensor.h"
#include "AP_InertialSensor_Backend.h" #include "AP_InertialSensor_Backend.h"
@ -26,6 +28,9 @@ public:
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu, static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev); AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev);
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
/** /**
* Configure the sensors and start reading routine. * Configure the sensors and start reading routine.
*/ */