AP_InertialSensor_L3G4200D.h 985 B

123456789101112131415161718192021222324252627282930313233343536373839
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  4. #include <AP_HAL/I2CDevice.h>
  5. #include <Filter/Filter.h>
  6. #include <Filter/LowPassFilter2p.h>
  7. #include "AP_InertialSensor.h"
  8. #include "AP_InertialSensor_Backend.h"
  9. class AP_InertialSensor_L3G4200D : public AP_InertialSensor_Backend
  10. {
  11. public:
  12. AP_InertialSensor_L3G4200D(AP_InertialSensor &imu,
  13. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  14. virtual ~AP_InertialSensor_L3G4200D();
  15. // probe the sensor on I2C bus
  16. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  17. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  18. /* update accel and gyro state */
  19. bool update() override;
  20. void start(void) override;
  21. private:
  22. bool _init_sensor();
  23. void _accumulate();
  24. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  25. // gyro and accel instances
  26. uint8_t _gyro_instance;
  27. uint8_t _accel_instance;
  28. };
  29. #endif