AP_InertialSensor_Invensense.h 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210
  1. #pragma once
  2. /*
  3. driver for the invensense range of IMUs, including:
  4. MPU6000
  5. MPU9250
  6. ICM-20608
  7. */
  8. #include <stdint.h>
  9. #include <AP_HAL/AP_HAL.h>
  10. #include <AP_HAL/I2CDevice.h>
  11. #include <AP_HAL/SPIDevice.h>
  12. #include <AP_HAL/utility/OwnPtr.h>
  13. #include <AP_Math/AP_Math.h>
  14. #include <Filter/Filter.h>
  15. #include <Filter/LowPassFilter.h>
  16. #include <Filter/LowPassFilter2p.h>
  17. #include "AP_InertialSensor.h"
  18. #include "AP_InertialSensor_Backend.h"
  19. #include "AuxiliaryBus.h"
  20. class AP_Invensense_AuxiliaryBus;
  21. class AP_Invensense_AuxiliaryBusSlave;
  22. class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend
  23. {
  24. friend AP_Invensense_AuxiliaryBus;
  25. friend AP_Invensense_AuxiliaryBusSlave;
  26. public:
  27. virtual ~AP_InertialSensor_Invensense();
  28. static AP_InertialSensor_Invensense &from(AP_InertialSensor_Backend &backend) {
  29. return static_cast<AP_InertialSensor_Invensense&>(backend);
  30. }
  31. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  32. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  33. enum Rotation rotation);
  34. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  35. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev,
  36. enum Rotation rotation);
  37. /* update accel and gyro state */
  38. bool update() override;
  39. void accumulate() override;
  40. /*
  41. * Return an AuxiliaryBus if the bus driver allows it
  42. */
  43. AuxiliaryBus *get_auxiliary_bus() override;
  44. void start() override;
  45. enum Invensense_Type {
  46. Invensense_MPU6000=0,
  47. Invensense_MPU6500,
  48. Invensense_MPU9250,
  49. Invensense_ICM20608,
  50. Invensense_ICM20602,
  51. Invensense_ICM20601,
  52. Invensense_ICM20789,
  53. Invensense_ICM20689,
  54. };
  55. // acclerometers on Invensense sensors will return values up to
  56. // 24G, but they are not guaranteed to be remotely linear past
  57. // 16G
  58. const uint16_t multiplier_accel = INT16_MAX/(26*GRAVITY_MSS);
  59. private:
  60. AP_InertialSensor_Invensense(AP_InertialSensor &imu,
  61. AP_HAL::OwnPtr<AP_HAL::Device> dev,
  62. enum Rotation rotation);
  63. /* Initialize sensor*/
  64. bool _init();
  65. bool _hardware_init();
  66. bool _check_whoami();
  67. void _set_filter_register(void);
  68. void _fifo_reset();
  69. bool _has_auxiliary_bus();
  70. /* Read samples from FIFO (FIFO enabled) */
  71. void _read_fifo();
  72. /* Check if there's data available by either reading DRDY pin or register */
  73. bool _data_ready();
  74. /* Poll for new data (non-blocking) */
  75. void _poll_data();
  76. /* Read and write functions taking the differences between buses into
  77. * account */
  78. bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
  79. uint8_t _register_read(uint8_t reg);
  80. void _register_write(uint8_t reg, uint8_t val, bool checked=false);
  81. bool _accumulate(uint8_t *samples, uint8_t n_samples);
  82. bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples);
  83. bool _check_raw_temp(int16_t t2);
  84. int16_t _raw_temp;
  85. // instance numbers of accel and gyro data
  86. uint8_t _gyro_instance;
  87. uint8_t _accel_instance;
  88. float temp_sensitivity = 1.0f/340; // degC/LSB
  89. float temp_zero = 36.53f; // degC
  90. float _temp_filtered;
  91. float _accel_scale;
  92. float _gyro_scale;
  93. float _fifo_accel_scale;
  94. float _fifo_gyro_scale;
  95. LowPassFilter2pFloat _temp_filter;
  96. enum Rotation _rotation;
  97. AP_HAL::DigitalSource *_drdy_pin;
  98. AP_HAL::OwnPtr<AP_HAL::Device> _dev;
  99. AP_Invensense_AuxiliaryBus *_auxiliary_bus;
  100. // which sensor type this is
  101. enum Invensense_Type _mpu_type;
  102. // are we doing more than 1kHz sampling?
  103. bool _fast_sampling;
  104. // what downsampling rate are we using from the FIFO?
  105. uint8_t _fifo_downsample_rate;
  106. // what rate are we generating samples into the backend?
  107. uint16_t _backend_rate_hz;
  108. // Last status from register user control
  109. uint8_t _last_stat_user_ctrl;
  110. // buffer for fifo read
  111. uint8_t *_fifo_buffer;
  112. /*
  113. accumulators for sensor_rate sampling
  114. See description in _accumulate_sensor_rate_sampling()
  115. */
  116. struct {
  117. Vector3f accel;
  118. Vector3f gyro;
  119. uint8_t count;
  120. LowPassFilterVector3f accel_filter{4000, 188};
  121. LowPassFilterVector3f gyro_filter{8000, 188};
  122. } _accum;
  123. };
  124. class AP_Invensense_AuxiliaryBusSlave : public AuxiliaryBusSlave
  125. {
  126. friend class AP_Invensense_AuxiliaryBus;
  127. public:
  128. int passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) override;
  129. int passthrough_write(uint8_t reg, uint8_t val) override;
  130. int read(uint8_t *buf) override;
  131. protected:
  132. AP_Invensense_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance);
  133. int _set_passthrough(uint8_t reg, uint8_t size, uint8_t *out = nullptr);
  134. private:
  135. const uint8_t _mpu_addr;
  136. const uint8_t _mpu_reg;
  137. const uint8_t _mpu_ctrl;
  138. const uint8_t _mpu_do;
  139. uint8_t _ext_sens_data = 0;
  140. };
  141. class AP_Invensense_AuxiliaryBus : public AuxiliaryBus
  142. {
  143. friend class AP_InertialSensor_Invensense;
  144. public:
  145. AP_HAL::Semaphore *get_semaphore() override;
  146. AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) override;
  147. protected:
  148. AP_Invensense_AuxiliaryBus(AP_InertialSensor_Invensense &backend, uint32_t devid);
  149. AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance) override;
  150. int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
  151. uint8_t size) override;
  152. private:
  153. void _configure_slaves();
  154. static const uint8_t MAX_EXT_SENS_DATA = 24;
  155. uint8_t _ext_sens_data = 0;
  156. };
  157. #ifndef INS_INVENSENSE_20789_I2C_ADDR
  158. #define INS_INVENSENSE_20789_I2C_ADDR 0x68
  159. #endif