AP_InertialSensor_RST.h 1.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556
  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 <AP_HAL/SPIDevice.h>
  6. #include <Filter/Filter.h>
  7. #include <Filter/LowPassFilter2p.h>
  8. #include "AP_InertialSensor.h"
  9. #include "AP_InertialSensor_Backend.h"
  10. class AP_InertialSensor_RST : public AP_InertialSensor_Backend
  11. {
  12. public:
  13. AP_InertialSensor_RST(AP_InertialSensor &imu,
  14. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
  15. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
  16. enum Rotation rotation_a,
  17. enum Rotation rotation_g);
  18. virtual ~AP_InertialSensor_RST();
  19. // probe the sensor on SPI bus
  20. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  21. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
  22. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
  23. enum Rotation rotation_a,
  24. enum Rotation rotation_g);
  25. /* update accel and gyro state */
  26. bool update() override;
  27. void start(void) override;
  28. private:
  29. bool _init_sensor();
  30. bool _init_gyro();
  31. bool _init_accel();
  32. void gyro_measure();
  33. void accel_measure();
  34. AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev_gyro;//i3g4250d
  35. AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev_accel;//iis328dq
  36. float _gyro_scale;
  37. float _accel_scale;
  38. // gyro and accel instances
  39. uint8_t _gyro_instance;
  40. uint8_t _accel_instance;
  41. enum Rotation _rotation_g;
  42. enum Rotation _rotation_a;
  43. };
  44. #endif