AP_InertialSensor_Invensensev2.h 5.7 KB

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