AP_InertialSensor_Backend.h 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. IMU driver backend class. Each supported gyro/accel sensor type
  15. needs to have an object derived from this class.
  16. Note that drivers can implement just gyros or just accels, and can
  17. also provide multiple gyro/accel instances.
  18. */
  19. #pragma once
  20. #include <inttypes.h>
  21. #include <AP_Math/AP_Math.h>
  22. #include "AP_InertialSensor.h"
  23. class AuxiliaryBus;
  24. class AP_Logger;
  25. class AP_InertialSensor_Backend
  26. {
  27. public:
  28. AP_InertialSensor_Backend(AP_InertialSensor &imu);
  29. AP_InertialSensor_Backend(const AP_InertialSensor_Backend &that) = delete;
  30. // we declare a virtual destructor so that drivers can
  31. // override with a custom destructor if need be.
  32. virtual ~AP_InertialSensor_Backend(void) {}
  33. /*
  34. * Update the sensor data. Called by the frontend to transfer
  35. * accumulated sensor readings to the frontend structure via the
  36. * _publish_gyro() and _publish_accel() functions
  37. */
  38. virtual bool update() = 0;
  39. /*
  40. * optional function to accumulate more samples. This is needed for drivers that don't use a timer to gather samples
  41. */
  42. virtual void accumulate() {}
  43. /*
  44. * Configure and start all sensors. The empty implementation allows
  45. * subclasses to already start the sensors when it's detected
  46. */
  47. virtual void start() { }
  48. /*
  49. * Return an AuxiliaryBus if backend has another bus it is able to export
  50. */
  51. virtual AuxiliaryBus *get_auxiliary_bus() { return nullptr; }
  52. /*
  53. * Return the unique identifier for this backend: it's the same for
  54. * several sensors if the backend registers more gyros/accels
  55. */
  56. int16_t get_id() const { return _id; }
  57. //Returns the Clip Limit
  58. float get_clip_limit() const { return _clip_limit; }
  59. // notify of a fifo reset
  60. void notify_fifo_reset(void);
  61. /*
  62. device driver IDs. These are used to fill in the devtype field
  63. of the device ID, which shows up as INS*ID* parameters to
  64. users. The values are chosen for compatibility with existing PX4
  65. drivers.
  66. If a change is made to a driver that would make existing
  67. calibration values invalid then this number must be changed.
  68. */
  69. enum DevTypes {
  70. DEVTYPE_BMI160 = 0x09,
  71. DEVTYPE_L3G4200D = 0x10,
  72. DEVTYPE_ACC_LSM303D = 0x11,
  73. DEVTYPE_ACC_BMA180 = 0x12,
  74. DEVTYPE_ACC_MPU6000 = 0x13,
  75. DEVTYPE_ACC_MPU9250 = 0x16,
  76. DEVTYPE_ACC_IIS328DQ = 0x17,
  77. DEVTYPE_ACC_LSM9DS1 = 0x18,
  78. DEVTYPE_GYR_MPU6000 = 0x21,
  79. DEVTYPE_GYR_L3GD20 = 0x22,
  80. DEVTYPE_GYR_MPU9250 = 0x24,
  81. DEVTYPE_GYR_I3G4250D = 0x25,
  82. DEVTYPE_GYR_LSM9DS1 = 0x26,
  83. DEVTYPE_INS_ICM20789 = 0x27,
  84. DEVTYPE_INS_ICM20689 = 0x28,
  85. DEVTYPE_INS_BMI055 = 0x29,
  86. DEVTYPE_SITL = 0x2A,
  87. DEVTYPE_INS_BMI088 = 0x2B,
  88. DEVTYPE_INS_ICM20948 = 0x2C,
  89. DEVTYPE_INS_ICM20648 = 0x2D,
  90. DEVTYPE_INS_ICM20649 = 0x2E,
  91. DEVTYPE_INS_ICM20602 = 0x2F,
  92. DEVTYPE_INS_ICM20601 = 0x30,
  93. };
  94. protected:
  95. // access to frontend
  96. AP_InertialSensor &_imu;
  97. // semaphore for access to shared frontend data
  98. HAL_Semaphore_Recursive _sem;
  99. //Default Clip Limit
  100. float _clip_limit = 15.5f * GRAVITY_MSS;
  101. void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel);
  102. void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro);
  103. // rotate gyro vector, offset and publish
  104. void _publish_gyro(uint8_t instance, const Vector3f &gyro);
  105. // this should be called every time a new gyro raw sample is
  106. // available - be it published or not the sample is raw in the
  107. // sense that it's not filtered yet, but it must be rotated and
  108. // corrected (_rotate_and_correct_gyro)
  109. // The sample_us value must be provided for non-FIFO based
  110. // sensors, and should be set to zero for FIFO based sensors
  111. void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0);
  112. // rotate accel vector, scale, offset and publish
  113. void _publish_accel(uint8_t instance, const Vector3f &accel);
  114. // this should be called every time a new accel raw sample is available -
  115. // be it published or not
  116. // the sample is raw in the sense that it's not filtered yet, but it must
  117. // be rotated and corrected (_rotate_and_correct_accel)
  118. // The sample_us value must be provided for non-FIFO based
  119. // sensors, and should be set to zero for FIFO based sensors
  120. void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false);
  121. // set the amount of oversamping a accel is doing
  122. void _set_accel_oversampling(uint8_t instance, uint8_t n);
  123. // set the amount of oversamping a gyro is doing
  124. void _set_gyro_oversampling(uint8_t instance, uint8_t n);
  125. // indicate the backend is doing sensor-rate sampling for this accel
  126. void _set_accel_sensor_rate_sampling_enabled(uint8_t instance, bool value) {
  127. const uint8_t bit = (1<<instance);
  128. if (value) {
  129. _imu._accel_sensor_rate_sampling_enabled |= bit;
  130. } else {
  131. _imu._accel_sensor_rate_sampling_enabled &= ~bit;
  132. }
  133. }
  134. void _set_gyro_sensor_rate_sampling_enabled(uint8_t instance, bool value) {
  135. const uint8_t bit = (1<<instance);
  136. if (value) {
  137. _imu._gyro_sensor_rate_sampling_enabled |= bit;
  138. } else {
  139. _imu._gyro_sensor_rate_sampling_enabled &= ~bit;
  140. }
  141. }
  142. void _set_raw_sample_accel_multiplier(uint8_t instance, uint16_t mul) {
  143. _imu._accel_raw_sampling_multiplier[instance] = mul;
  144. }
  145. void _set_raw_sampl_gyro_multiplier(uint8_t instance, uint16_t mul) {
  146. _imu._gyro_raw_sampling_multiplier[instance] = mul;
  147. }
  148. // update the sensor rate for FIFO sensors
  149. void _update_sensor_rate(uint16_t &count, uint32_t &start_us, float &rate_hz) const;
  150. // return true if the sensors are still converging and sampling rates could change significantly
  151. bool sensors_converging() const { return AP_HAL::millis() < 30000; }
  152. // set accelerometer max absolute offset for calibration
  153. void _set_accel_max_abs_offset(uint8_t instance, float offset);
  154. // get accelerometer raw sample rate.
  155. float _accel_raw_sample_rate(uint8_t instance) const {
  156. return _imu._accel_raw_sample_rates[instance];
  157. }
  158. // set accelerometer raw sample rate; note that the storage type
  159. // is actually float!
  160. void _set_accel_raw_sample_rate(uint8_t instance, uint16_t rate_hz) {
  161. _imu._accel_raw_sample_rates[instance] = rate_hz;
  162. }
  163. // get gyroscope raw sample rate
  164. float _gyro_raw_sample_rate(uint8_t instance) const {
  165. return _imu._gyro_raw_sample_rates[instance];
  166. }
  167. // set gyro raw sample rate; note that the storage type is
  168. // actually float!
  169. void _set_gyro_raw_sample_rate(uint8_t instance, uint16_t rate_hz) {
  170. _imu._gyro_raw_sample_rates[instance] = rate_hz;
  171. }
  172. // publish a temperature value
  173. void _publish_temperature(uint8_t instance, float temperature);
  174. // set accelerometer error_count
  175. void _set_accel_error_count(uint8_t instance, uint32_t error_count);
  176. // set gyro error_count
  177. void _set_gyro_error_count(uint8_t instance, uint32_t error_count);
  178. // increment accelerometer error_count
  179. void _inc_accel_error_count(uint8_t instance);
  180. // increment gyro error_count
  181. void _inc_gyro_error_count(uint8_t instance);
  182. // backend unique identifier or -1 if backend doesn't identify itself
  183. int16_t _id = -1;
  184. // return the default filter frequency in Hz for the sample rate
  185. uint16_t _accel_filter_cutoff(void) const { return _imu._accel_filter_cutoff; }
  186. // return the default filter frequency in Hz for the sample rate
  187. uint16_t _gyro_filter_cutoff(void) const { return _imu._gyro_filter_cutoff; }
  188. // return the requested sample rate in Hz
  189. uint16_t get_sample_rate_hz(void) const;
  190. // return the notch filter center in Hz for the sample rate
  191. float _gyro_notch_center_freq_hz(void) const { return _imu._notch_filter.center_freq_hz(); }
  192. // return the notch filter bandwidth in Hz for the sample rate
  193. float _gyro_notch_bandwidth_hz(void) const { return _imu._notch_filter.bandwidth_hz(); }
  194. // return the notch filter attenuation in dB for the sample rate
  195. float _gyro_notch_attenuation_dB(void) const { return _imu._notch_filter.attenuation_dB(); }
  196. uint8_t _gyro_notch_enabled(void) const { return _imu._notch_filter.enabled(); }
  197. // return the harmonic notch filter center in Hz for the sample rate
  198. float gyro_harmonic_notch_center_freq_hz() const { return _imu._calculated_harmonic_notch_freq_hz; }
  199. // return the harmonic notch filter bandwidth in Hz for the sample rate
  200. float gyro_harmonic_notch_bandwidth_hz(void) const { return _imu._harmonic_notch_filter.bandwidth_hz(); }
  201. // return the harmonic notch filter attenuation in dB for the sample rate
  202. float gyro_harmonic_notch_attenuation_dB(void) const { return _imu._harmonic_notch_filter.attenuation_dB(); }
  203. uint8_t gyro_harmonic_notch_enabled(void) const { return _imu._harmonic_notch_filter.enabled(); }
  204. // common gyro update function for all backends
  205. void update_gyro(uint8_t instance);
  206. // common accel update function for all backends
  207. void update_accel(uint8_t instance);
  208. // support for updating filter at runtime
  209. uint16_t _last_accel_filter_hz;
  210. uint16_t _last_gyro_filter_hz;
  211. float _last_notch_center_freq_hz;
  212. float _last_notch_bandwidth_hz;
  213. float _last_notch_attenuation_dB;
  214. // support for updating harmonic filter at runtime
  215. float _last_harmonic_notch_center_freq_hz;
  216. float _last_harmonic_notch_bandwidth_hz;
  217. float _last_harmonic_notch_attenuation_dB;
  218. void set_gyro_orientation(uint8_t instance, enum Rotation rotation) {
  219. _imu._gyro_orientation[instance] = rotation;
  220. }
  221. void set_accel_orientation(uint8_t instance, enum Rotation rotation) {
  222. _imu._accel_orientation[instance] = rotation;
  223. }
  224. // increment clipping counted. Used by drivers that do decimation before supplying
  225. // samples to the frontend
  226. void increment_clip_count(uint8_t instance) {
  227. _imu._accel_clip_count[instance]++;
  228. }
  229. // should fast sampling be enabled on this IMU?
  230. bool enable_fast_sampling(uint8_t instance) {
  231. return (_imu._fast_sampling_mask & (1U<<instance)) != 0;
  232. }
  233. // called by subclass when data is received from the sensor, thus
  234. // at the 'sensor rate'
  235. void _notify_new_accel_sensor_rate_sample(uint8_t instance, const Vector3f &accel);
  236. void _notify_new_gyro_sensor_rate_sample(uint8_t instance, const Vector3f &gyro);
  237. /*
  238. notify of a FIFO reset so we don't use bad data to update observed sensor rate
  239. */
  240. void notify_accel_fifo_reset(uint8_t instance);
  241. void notify_gyro_fifo_reset(uint8_t instance);
  242. // note that each backend is also expected to have a static detect()
  243. // function which instantiates an instance of the backend sensor
  244. // driver if the sensor is available
  245. private:
  246. bool should_log_imu_raw() const;
  247. void log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel);
  248. void log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gryo);
  249. };