APM:Libraries
AP_InertialSensor_L3G4200D.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
5 
6 #include <AP_HAL/I2CDevice.h>
7 #include <Filter/Filter.h>
9 
10 #include "AP_InertialSensor.h"
12 
14 {
15 public:
19 
20  // probe the sensor on I2C bus
23 
24  /* update accel and gyro state */
25  bool update() override;
26 
27  void start(void) override;
28 
29 private:
30  bool _init_sensor();
31  void _accumulate();
32 
34 
35  // gyro and accel instances
36  uint8_t _gyro_instance;
37  uint8_t _accel_instance;
38 };
39 #endif
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
A class to implement a second order low pass filter.
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
AP_InertialSensor_L3G4200D(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)