|
|
|
@ -16,16 +16,16 @@ public:
@@ -16,16 +16,16 @@ public:
|
|
|
|
|
bool update() override; |
|
|
|
|
|
|
|
|
|
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev_accel, |
|
|
|
|
enum Rotation rotation_a = ROTATION_NONE, |
|
|
|
|
enum Rotation rotation_g = ROTATION_NONE, |
|
|
|
|
enum Rotation rotation_gH = ROTATION_NONE); |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro, |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev_accel, |
|
|
|
|
int drdy_pin_num_a, int drdy_pin_num_b, |
|
|
|
|
enum Rotation rotation_a, |
|
|
|
|
enum Rotation rotation_g, |
|
|
|
@ -80,8 +80,8 @@ private:
@@ -80,8 +80,8 @@ private:
|
|
|
|
|
void _dump_registers(); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev_gyro; |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev_accel; |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev_gyro; |
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev_accel; |
|
|
|
|
AP_HAL::Semaphore *_spi_sem; |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|