AP_InertialSensor_LSM9DS0.h 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112
  1. #pragma once
  2. #define LSM9DS0_DEBUG 0
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_HAL/SPIDevice.h>
  5. #include "AP_InertialSensor.h"
  6. #include "AP_InertialSensor_Backend.h"
  7. class AP_InertialSensor_LSM9DS0 : public AP_InertialSensor_Backend
  8. {
  9. public:
  10. virtual ~AP_InertialSensor_LSM9DS0() { }
  11. void start(void) override;
  12. bool update() override;
  13. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  14. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro,
  15. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel,
  16. enum Rotation rotation_a,
  17. enum Rotation rotation_g,
  18. enum Rotation rotation_gH);
  19. private:
  20. AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu,
  21. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro,
  22. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel,
  23. int drdy_pin_num_a, int drdy_pin_num_b,
  24. enum Rotation rotation_a,
  25. enum Rotation rotation_g,
  26. enum Rotation rotation_gH);
  27. struct PACKED sensor_raw_data {
  28. int16_t x;
  29. int16_t y;
  30. int16_t z;
  31. };
  32. enum gyro_scale {
  33. G_SCALE_245DPS = 0,
  34. G_SCALE_500DPS,
  35. G_SCALE_2000DPS,
  36. };
  37. enum accel_scale {
  38. A_SCALE_2G = 0,
  39. A_SCALE_4G,
  40. A_SCALE_6G,
  41. A_SCALE_8G,
  42. A_SCALE_16G,
  43. };
  44. bool _accel_data_ready();
  45. bool _gyro_data_ready();
  46. void _poll_data();
  47. bool _init_sensor();
  48. bool _hardware_init();
  49. void _gyro_init();
  50. void _accel_init();
  51. void _gyro_disable_i2c();
  52. void _accel_disable_i2c();
  53. void _set_gyro_scale(gyro_scale scale);
  54. void _set_accel_scale(accel_scale scale);
  55. uint8_t _register_read_xm(uint8_t reg);
  56. uint8_t _register_read_g(uint8_t reg);
  57. void _register_write_xm(uint8_t reg, uint8_t val, bool checked=false);
  58. void _register_write_g(uint8_t reg, uint8_t val, bool checked=false);
  59. void _read_data_transaction_a();
  60. void _read_data_transaction_g();
  61. #if LSM9DS0_DEBUG
  62. void _dump_registers();
  63. #endif
  64. AP_HAL::OwnPtr<AP_HAL::Device> _dev_gyro;
  65. AP_HAL::OwnPtr<AP_HAL::Device> _dev_accel;
  66. AP_HAL::Semaphore *_spi_sem;
  67. /*
  68. * If data-ready GPIO pins numbers are not defined (i.e. any negative
  69. * value), the fallback approach used is to check if there's new data ready
  70. * by reading the status register. It is *strongly* recommended to use
  71. * data-ready GPIO pins for performance reasons.
  72. */
  73. AP_HAL::DigitalSource * _drdy_pin_a;
  74. AP_HAL::DigitalSource * _drdy_pin_g;
  75. float _gyro_scale;
  76. float _accel_scale;
  77. int _drdy_pin_num_a;
  78. int _drdy_pin_num_g;
  79. uint8_t _gyro_instance;
  80. uint8_t _accel_instance;
  81. // gyro whoami
  82. uint8_t whoami_g;
  83. /*
  84. for boards that have a separate LSM303D and L3GD20 there can be
  85. different rotations for each
  86. */
  87. enum Rotation _rotation_a;
  88. enum Rotation _rotation_g; // for L3GD20
  89. enum Rotation _rotation_gH; // for L3GD20H
  90. };