AP_InertialSensor.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615
  1. #pragma once
  2. // Gyro and Accelerometer calibration criteria
  3. #define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f
  4. #define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0f
  5. #define AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ 5.0f // accel vibration floor filter hz
  6. #define AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ 2.0f // accel vibration filter hz
  7. #define AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS 500 // peak-hold detector timeout
  8. /**
  9. maximum number of INS instances available on this platform. If more
  10. than 1 then redundant sensors may be available
  11. */
  12. #define INS_MAX_INSTANCES 3
  13. #define INS_MAX_BACKENDS 6
  14. #define INS_VIBRATION_CHECK_INSTANCES 2
  15. #define DEFAULT_IMU_LOG_BAT_MASK 0
  16. #include <stdint.h>
  17. #include <AP_AccelCal/AP_AccelCal.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include <Filter/LowPassFilter2p.h>
  21. #include <Filter/LowPassFilter.h>
  22. #include <Filter/NotchFilter.h>
  23. #include <Filter/HarmonicNotchFilter.h>
  24. class AP_InertialSensor_Backend;
  25. class AuxiliaryBus;
  26. class AP_AHRS;
  27. /*
  28. forward declare AP_Logger class. We can't include logger.h
  29. because of mutual dependencies
  30. */
  31. class AP_Logger;
  32. /* AP_InertialSensor is an abstraction for gyro and accel measurements
  33. * which are correctly aligned to the body axes and scaled to SI units.
  34. *
  35. * Gauss-Newton accel calibration routines borrowed from Rolfe Schmidt
  36. * blog post describing the method: http://chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/
  37. * original sketch available at http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde
  38. */
  39. class AP_InertialSensor : AP_AccelCal_Client
  40. {
  41. friend class AP_InertialSensor_Backend;
  42. public:
  43. AP_InertialSensor();
  44. /* Do not allow copies */
  45. AP_InertialSensor(const AP_InertialSensor &other) = delete;
  46. AP_InertialSensor &operator=(const AP_InertialSensor&) = delete;
  47. static AP_InertialSensor *get_singleton();
  48. enum Gyro_Calibration_Timing {
  49. GYRO_CAL_NEVER = 0,
  50. GYRO_CAL_STARTUP_ONLY = 1
  51. };
  52. /// Perform startup initialisation.
  53. ///
  54. /// Called to initialise the state of the IMU.
  55. ///
  56. /// Gyros will be calibrated unless INS_GYRO_CAL is zero
  57. ///
  58. /// @param style The initialisation startup style.
  59. ///
  60. void init(uint16_t sample_rate_hz);
  61. /// Register a new gyro/accel driver, allocating an instance
  62. /// number
  63. uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id);
  64. uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id);
  65. // a function called by the main thread at the main loop rate:
  66. void periodic();
  67. bool calibrate_trim(float &trim_roll, float &trim_pitch);
  68. /// calibrating - returns true if the gyros or accels are currently being calibrated
  69. bool calibrating() const { return _calibrating; }
  70. /// Perform cold-start initialisation for just the gyros.
  71. ///
  72. /// @note This should not be called unless ::init has previously
  73. /// been called, as ::init may perform other work
  74. ///
  75. void init_gyro(void);
  76. /// Fetch the current gyro values
  77. ///
  78. /// @returns vector of rotational rates in radians/sec
  79. ///
  80. const Vector3f &get_gyro(uint8_t i) const { return _gyro[i]; }
  81. const Vector3f &get_gyro(void) const { return get_gyro(_primary_gyro); }
  82. // set gyro offsets in radians/sec
  83. const Vector3f &get_gyro_offsets(uint8_t i) const { return _gyro_offset[i]; }
  84. const Vector3f &get_gyro_offsets(void) const { return get_gyro_offsets(_primary_gyro); }
  85. //get delta angle if available
  86. bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const;
  87. bool get_delta_angle(Vector3f &delta_angle) const { return get_delta_angle(_primary_gyro, delta_angle); }
  88. float get_delta_angle_dt(uint8_t i) const;
  89. float get_delta_angle_dt() const { return get_delta_angle_dt(_primary_accel); }
  90. //get delta velocity if available
  91. bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const;
  92. bool get_delta_velocity(Vector3f &delta_velocity) const { return get_delta_velocity(_primary_accel, delta_velocity); }
  93. float get_delta_velocity_dt(uint8_t i) const;
  94. float get_delta_velocity_dt() const { return get_delta_velocity_dt(_primary_accel); }
  95. /// Fetch the current accelerometer values
  96. ///
  97. /// @returns vector of current accelerations in m/s/s
  98. ///
  99. const Vector3f &get_accel(uint8_t i) const { return _accel[i]; }
  100. const Vector3f &get_accel(void) const { return get_accel(_primary_accel); }
  101. uint32_t get_gyro_error_count(uint8_t i) const { return _gyro_error_count[i]; }
  102. uint32_t get_accel_error_count(uint8_t i) const { return _accel_error_count[i]; }
  103. // multi-device interface
  104. bool get_gyro_health(uint8_t instance) const { return (instance<_gyro_count) ? _gyro_healthy[instance] : false; }
  105. bool get_gyro_health(void) const { return get_gyro_health(_primary_gyro); }
  106. bool get_gyro_health_all(void) const;
  107. uint8_t get_gyro_count(void) const { return _gyro_count; }
  108. bool gyro_calibrated_ok(uint8_t instance) const { return _gyro_cal_ok[instance]; }
  109. bool gyro_calibrated_ok_all() const;
  110. bool use_gyro(uint8_t instance) const;
  111. Gyro_Calibration_Timing gyro_calibration_timing();
  112. bool get_accel_health(uint8_t instance) const { return (instance<_accel_count) ? _accel_healthy[instance] : false; }
  113. bool get_accel_health(void) const { return get_accel_health(_primary_accel); }
  114. bool get_accel_health_all(void) const;
  115. uint8_t get_accel_count(void) const { return _accel_count; }
  116. bool accel_calibrated_ok_all() const;
  117. bool use_accel(uint8_t instance) const;
  118. // get observed sensor rates, including any internal sampling multiplier
  119. uint16_t get_gyro_rate_hz(uint8_t instance) const { return uint16_t(_gyro_raw_sample_rates[instance] * _gyro_over_sampling[instance]); }
  120. uint16_t get_accel_rate_hz(uint8_t instance) const { return uint16_t(_accel_raw_sample_rates[instance] * _accel_over_sampling[instance]); }
  121. // get accel offsets in m/s/s
  122. const Vector3f &get_accel_offsets(uint8_t i) const { return _accel_offset[i]; }
  123. const Vector3f &get_accel_offsets(void) const { return get_accel_offsets(_primary_accel); }
  124. // get accel scale
  125. const Vector3f &get_accel_scale(uint8_t i) const { return _accel_scale[i]; }
  126. const Vector3f &get_accel_scale(void) const { return get_accel_scale(_primary_accel); }
  127. // return a 3D vector defining the position offset of the IMU accelerometer in metres relative to the body frame origin
  128. const Vector3f &get_imu_pos_offset(uint8_t instance) const {
  129. return _accel_pos[instance];
  130. }
  131. const Vector3f &get_imu_pos_offset(void) const {
  132. return _accel_pos[_primary_accel];
  133. }
  134. // return the temperature if supported. Zero is returned if no
  135. // temperature is available
  136. float get_temperature(uint8_t instance) const { return _temperature[instance]; }
  137. /* get_delta_time returns the time period in seconds
  138. * overwhich the sensor data was collected
  139. */
  140. float get_delta_time() const { return MIN(_delta_time, _loop_delta_t_max); }
  141. // return the maximum gyro drift rate in radians/s/s. This
  142. // depends on what gyro chips are being used
  143. float get_gyro_drift_rate(void) const { return ToRad(0.5f/60); }
  144. // update gyro and accel values from accumulated samples
  145. void update(void);
  146. // wait for a sample to be available
  147. void wait_for_sample(void);
  148. // class level parameters
  149. static const struct AP_Param::GroupInfo var_info[];
  150. // set overall board orientation
  151. void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
  152. _board_orientation = orientation;
  153. _custom_rotation = custom_rotation;
  154. }
  155. // return the selected sample rate
  156. uint16_t get_sample_rate(void) const { return _sample_rate; }
  157. // return the main loop delta_t in seconds
  158. float get_loop_delta_t(void) const { return _loop_delta_t; }
  159. bool healthy(void) const { return get_gyro_health() && get_accel_health(); }
  160. uint8_t get_primary_accel(void) const { return _primary_accel; }
  161. uint8_t get_primary_gyro(void) const { return _primary_gyro; }
  162. // Update the harmonic notch frequency
  163. void update_harmonic_notch_freq_hz(float scaled_freq);
  164. // enable HIL mode
  165. void set_hil_mode(void) { _hil_mode = true; }
  166. // get the gyro filter rate in Hz
  167. uint16_t get_gyro_filter_hz(void) const { return _gyro_filter_cutoff; }
  168. // get the accel filter rate in Hz
  169. uint16_t get_accel_filter_hz(void) const { return _accel_filter_cutoff; }
  170. // harmonic notch current center frequency
  171. float get_gyro_dynamic_notch_center_freq_hz(void) const { return _calculated_harmonic_notch_freq_hz; }
  172. // harmonic notch reference center frequency
  173. float get_gyro_harmonic_notch_center_freq_hz(void) const { return _harmonic_notch_filter.center_freq_hz(); }
  174. // harmonic notch reference scale factor
  175. float get_gyro_harmonic_notch_reference(void) const { return _harmonic_notch_filter.reference(); }
  176. // indicate which bit in LOG_BITMASK indicates raw logging enabled
  177. void set_log_raw_bit(uint32_t log_raw_bit) { _log_raw_bit = log_raw_bit; }
  178. // calculate vibration levels and check for accelerometer clipping (called by a backends)
  179. void calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt);
  180. // retrieve latest calculated vibration levels
  181. Vector3f get_vibration_levels() const { return get_vibration_levels(_primary_accel); }
  182. Vector3f get_vibration_levels(uint8_t instance) const;
  183. // retrieve and clear accelerometer clipping count
  184. uint32_t get_accel_clip_count(uint8_t instance) const;
  185. // check for vibration movement. True when all axis show nearly zero movement
  186. bool is_still();
  187. /*
  188. HIL set functions. The minimum for HIL is set_accel() and
  189. set_gyro(). The others are option for higher fidelity log
  190. playback
  191. */
  192. void set_accel(uint8_t instance, const Vector3f &accel);
  193. void set_gyro(uint8_t instance, const Vector3f &gyro);
  194. void set_delta_time(float delta_time);
  195. void set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav);
  196. void set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat);
  197. AuxiliaryBus *get_auxiliary_bus(int16_t backend_id) { return get_auxiliary_bus(backend_id, 0); }
  198. AuxiliaryBus *get_auxiliary_bus(int16_t backend_id, uint8_t instance);
  199. void detect_backends(void);
  200. // accel peak hold detector
  201. void set_accel_peak_hold(uint8_t instance, const Vector3f &accel);
  202. float get_accel_peak_hold_neg_x() const { return _peak_hold_state.accel_peak_hold_neg_x; }
  203. //Returns accel calibrator interface object pointer
  204. AP_AccelCal* get_acal() const { return _acal; }
  205. // Returns body fixed accelerometer level data averaged during accel calibration's first step
  206. bool get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vector3f& ret) const;
  207. // Returns primary accelerometer level data averaged during accel calibration's first step
  208. bool get_primary_accel_cal_sample_avg(uint8_t sample_num, Vector3f& ret) const;
  209. // Returns newly calculated trim values if calculated
  210. bool get_new_trim(float& trim_roll, float &trim_pitch);
  211. // initialise and register accel calibrator
  212. // called during the startup of accel cal
  213. void acal_init();
  214. // update accel calibrator
  215. void acal_update();
  216. // simple accel calibration
  217. MAV_RESULT simple_accel_cal();
  218. bool accel_cal_requires_reboot() const { return _accel_cal_requires_reboot; }
  219. // return time in microseconds of last update() call
  220. uint32_t get_last_update_usec(void) const { return _last_update_usec; }
  221. // for killing an IMU for testing purposes
  222. void kill_imu(uint8_t imu_idx, bool kill_it);
  223. enum IMU_SENSOR_TYPE {
  224. IMU_SENSOR_TYPE_ACCEL = 0,
  225. IMU_SENSOR_TYPE_GYRO = 1,
  226. };
  227. class BatchSampler {
  228. public:
  229. BatchSampler(const AP_InertialSensor &imu) :
  230. type(IMU_SENSOR_TYPE_ACCEL),
  231. _imu(imu) {
  232. AP_Param::setup_object_defaults(this, var_info);
  233. };
  234. void init();
  235. void sample(uint8_t instance, IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &sample);
  236. // a function called by the main thread at the main loop rate:
  237. void periodic();
  238. bool doing_sensor_rate_logging() const { return _doing_sensor_rate_logging; }
  239. bool doing_post_filter_logging() const { return _doing_post_filter_logging; }
  240. // class level parameters
  241. static const struct AP_Param::GroupInfo var_info[];
  242. // Parameters
  243. AP_Int16 _required_count;
  244. AP_Int8 _sensor_mask;
  245. AP_Int8 _batch_options_mask;
  246. // Parameters controlling pushing data to AP_Logger:
  247. // Each DF message is ~ 108 bytes in size, so we use about 1kB/s of
  248. // logging bandwidth with a 100ms interval. If we are taking
  249. // 1024 samples then we need to send 32 packets, so it will
  250. // take ~3 seconds to push a complete batch to the log. If
  251. // you are running a on an FMU with three IMUs then you
  252. // will loop back around to the first sensor after about
  253. // twenty seconds.
  254. AP_Int16 samples_per_msg;
  255. AP_Int8 push_interval_ms;
  256. // end Parameters
  257. private:
  258. enum batch_opt_t {
  259. BATCH_OPT_SENSOR_RATE = (1<<0),
  260. BATCH_OPT_POST_FILTER = (1<<1),
  261. };
  262. void rotate_to_next_sensor();
  263. void update_doing_sensor_rate_logging();
  264. bool should_log(uint8_t instance, IMU_SENSOR_TYPE type);
  265. void push_data_to_log();
  266. uint64_t measurement_started_us;
  267. bool initialised : 1;
  268. bool isbh_sent : 1;
  269. bool _doing_sensor_rate_logging : 1;
  270. bool _doing_post_filter_logging : 1;
  271. uint8_t instance : 3; // instance we are sending data for
  272. AP_InertialSensor::IMU_SENSOR_TYPE type : 1;
  273. uint16_t isb_seqnum;
  274. int16_t *data_x;
  275. int16_t *data_y;
  276. int16_t *data_z;
  277. uint16_t data_write_offset; // units: samples
  278. uint16_t data_read_offset; // units: samples
  279. uint32_t last_sent_ms;
  280. // all samples are multiplied by this
  281. uint16_t multiplier; // initialised as part of init()
  282. const AP_InertialSensor &_imu;
  283. };
  284. BatchSampler batchsampler{*this};
  285. private:
  286. // load backend drivers
  287. bool _add_backend(AP_InertialSensor_Backend *backend);
  288. void _start_backends();
  289. AP_InertialSensor_Backend *_find_backend(int16_t backend_id, uint8_t instance);
  290. // gyro initialisation
  291. void _init_gyro();
  292. // Calibration routines borrowed from Rolfe Schmidt
  293. // blog post describing the method: http://chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/
  294. // original sketch available at http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde
  295. bool _calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch);
  296. // save gyro calibration values to eeprom
  297. void _save_gyro_calibration();
  298. // backend objects
  299. AP_InertialSensor_Backend *_backends[INS_MAX_BACKENDS];
  300. // number of gyros and accel drivers. Note that most backends
  301. // provide both accel and gyro data, so will increment both
  302. // counters on initialisation
  303. uint8_t _gyro_count;
  304. uint8_t _accel_count;
  305. uint8_t _backend_count;
  306. // the selected sample rate
  307. uint16_t _sample_rate;
  308. float _loop_delta_t;
  309. float _loop_delta_t_max;
  310. // Most recent accelerometer reading
  311. Vector3f _accel[INS_MAX_INSTANCES];
  312. Vector3f _delta_velocity[INS_MAX_INSTANCES];
  313. float _delta_velocity_dt[INS_MAX_INSTANCES];
  314. bool _delta_velocity_valid[INS_MAX_INSTANCES];
  315. // delta velocity accumulator
  316. Vector3f _delta_velocity_acc[INS_MAX_INSTANCES];
  317. // time accumulator for delta velocity accumulator
  318. float _delta_velocity_acc_dt[INS_MAX_INSTANCES];
  319. // Low Pass filters for gyro and accel
  320. LowPassFilter2pVector3f _accel_filter[INS_MAX_INSTANCES];
  321. LowPassFilter2pVector3f _gyro_filter[INS_MAX_INSTANCES];
  322. Vector3f _accel_filtered[INS_MAX_INSTANCES];
  323. Vector3f _gyro_filtered[INS_MAX_INSTANCES];
  324. bool _new_accel_data[INS_MAX_INSTANCES];
  325. bool _new_gyro_data[INS_MAX_INSTANCES];
  326. // optional notch filter on gyro
  327. NotchFilterParams _notch_filter;
  328. NotchFilterVector3f _gyro_notch_filter[INS_MAX_INSTANCES];
  329. // optional harmonic notch filter on gyro
  330. HarmonicNotchFilterParams _harmonic_notch_filter;
  331. HarmonicNotchFilterVector3f _gyro_harmonic_notch_filter[INS_MAX_INSTANCES];
  332. // the current center frequency for the notch
  333. float _calculated_harmonic_notch_freq_hz;
  334. // Most recent gyro reading
  335. Vector3f _gyro[INS_MAX_INSTANCES];
  336. Vector3f _delta_angle[INS_MAX_INSTANCES];
  337. float _delta_angle_dt[INS_MAX_INSTANCES];
  338. bool _delta_angle_valid[INS_MAX_INSTANCES];
  339. // time accumulator for delta angle accumulator
  340. float _delta_angle_acc_dt[INS_MAX_INSTANCES];
  341. Vector3f _delta_angle_acc[INS_MAX_INSTANCES];
  342. Vector3f _last_delta_angle[INS_MAX_INSTANCES];
  343. Vector3f _last_raw_gyro[INS_MAX_INSTANCES];
  344. // bitmask indicating if a sensor is doing sensor-rate sampling:
  345. uint8_t _accel_sensor_rate_sampling_enabled;
  346. uint8_t _gyro_sensor_rate_sampling_enabled;
  347. // multipliers for data supplied via sensor-rate logging:
  348. uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES];
  349. uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES];
  350. // IDs to uniquely identify each sensor: shall remain
  351. // the same across reboots
  352. AP_Int32 _accel_id[INS_MAX_INSTANCES];
  353. AP_Int32 _gyro_id[INS_MAX_INSTANCES];
  354. // accelerometer scaling and offsets
  355. AP_Vector3f _accel_scale[INS_MAX_INSTANCES];
  356. AP_Vector3f _accel_offset[INS_MAX_INSTANCES];
  357. AP_Vector3f _gyro_offset[INS_MAX_INSTANCES];
  358. // accelerometer position offset in body frame
  359. AP_Vector3f _accel_pos[INS_MAX_INSTANCES];
  360. // accelerometer max absolute offsets to be used for calibration
  361. float _accel_max_abs_offsets[INS_MAX_INSTANCES];
  362. // accelerometer and gyro raw sample rate in units of Hz
  363. float _accel_raw_sample_rates[INS_MAX_INSTANCES];
  364. float _gyro_raw_sample_rates[INS_MAX_INSTANCES];
  365. // how many sensors samples per notify to the backend
  366. uint8_t _accel_over_sampling[INS_MAX_INSTANCES];
  367. uint8_t _gyro_over_sampling[INS_MAX_INSTANCES];
  368. // last sample time in microseconds. Use for deltaT calculations
  369. // on non-FIFO sensors
  370. uint64_t _accel_last_sample_us[INS_MAX_INSTANCES];
  371. uint64_t _gyro_last_sample_us[INS_MAX_INSTANCES];
  372. // sample times for checking real sensor rate for FIFO sensors
  373. uint16_t _sample_accel_count[INS_MAX_INSTANCES];
  374. uint32_t _sample_accel_start_us[INS_MAX_INSTANCES];
  375. uint16_t _sample_gyro_count[INS_MAX_INSTANCES];
  376. uint32_t _sample_gyro_start_us[INS_MAX_INSTANCES];
  377. // temperatures for an instance if available
  378. float _temperature[INS_MAX_INSTANCES];
  379. // filtering frequency (0 means default)
  380. AP_Int16 _accel_filter_cutoff;
  381. AP_Int16 _gyro_filter_cutoff;
  382. AP_Int8 _gyro_cal_timing;
  383. // use for attitude, velocity, position estimates
  384. AP_Int8 _use[INS_MAX_INSTANCES];
  385. // control enable of fast sampling
  386. AP_Int8 _fast_sampling_mask;
  387. // control enable of detected sensors
  388. AP_Int8 _enable_mask;
  389. // board orientation from AHRS
  390. enum Rotation _board_orientation;
  391. Matrix3f* _custom_rotation;
  392. // per-sensor orientation to allow for board type defaults at runtime
  393. enum Rotation _gyro_orientation[INS_MAX_INSTANCES];
  394. enum Rotation _accel_orientation[INS_MAX_INSTANCES];
  395. // calibrated_ok/id_ok flags
  396. bool _gyro_cal_ok[INS_MAX_INSTANCES];
  397. bool _accel_id_ok[INS_MAX_INSTANCES];
  398. // primary accel and gyro
  399. uint8_t _primary_gyro;
  400. uint8_t _primary_accel;
  401. // mask of accels and gyros which we will be actively using
  402. // and this should wait for in wait_for_sample()
  403. uint8_t _gyro_wait_mask;
  404. uint8_t _accel_wait_mask;
  405. // bitmask bit which indicates if we should log raw accel and gyro data
  406. uint32_t _log_raw_bit;
  407. // has wait_for_sample() found a sample?
  408. bool _have_sample:1;
  409. // are we in HIL mode?
  410. bool _hil_mode:1;
  411. // are gyros or accels currently being calibrated
  412. bool _calibrating:1;
  413. bool _backends_detected:1;
  414. // the delta time in seconds for the last sample
  415. float _delta_time;
  416. // last time a wait_for_sample() returned a sample
  417. uint32_t _last_sample_usec;
  418. // target time for next wait_for_sample() return
  419. uint32_t _next_sample_usec;
  420. // time between samples in microseconds
  421. uint32_t _sample_period_usec;
  422. // last time update() completed
  423. uint32_t _last_update_usec;
  424. // health of gyros and accels
  425. bool _gyro_healthy[INS_MAX_INSTANCES];
  426. bool _accel_healthy[INS_MAX_INSTANCES];
  427. uint32_t _accel_error_count[INS_MAX_INSTANCES];
  428. uint32_t _gyro_error_count[INS_MAX_INSTANCES];
  429. // vibration and clipping
  430. uint32_t _accel_clip_count[INS_MAX_INSTANCES];
  431. LowPassFilterVector3f _accel_vibe_floor_filter[INS_VIBRATION_CHECK_INSTANCES];
  432. LowPassFilterVector3f _accel_vibe_filter[INS_VIBRATION_CHECK_INSTANCES];
  433. // peak hold detector state for primary accel
  434. struct PeakHoldState {
  435. float accel_peak_hold_neg_x;
  436. uint32_t accel_peak_hold_neg_x_age;
  437. } _peak_hold_state;
  438. // threshold for detecting stillness
  439. AP_Float _still_threshold;
  440. /*
  441. state for HIL support
  442. */
  443. struct {
  444. float delta_time;
  445. } _hil {};
  446. // Trim options
  447. AP_Int8 _acc_body_aligned;
  448. AP_Int8 _trim_option;
  449. static AP_InertialSensor *_singleton;
  450. AP_AccelCal* _acal;
  451. AccelCalibrator *_accel_calibrator;
  452. //save accelerometer bias and scale factors
  453. void _acal_save_calibrations() override;
  454. void _acal_event_failure() override;
  455. // Returns AccelCalibrator objects pointer for specified acceleromter
  456. AccelCalibrator* _acal_get_calibrator(uint8_t i) override { return i<get_accel_count()?&(_accel_calibrator[i]):nullptr; }
  457. float _trim_pitch;
  458. float _trim_roll;
  459. bool _new_trim;
  460. bool _accel_cal_requires_reboot;
  461. // sensor error count at startup (used to ignore errors within 2 seconds of startup)
  462. uint32_t _accel_startup_error_count[INS_MAX_INSTANCES];
  463. uint32_t _gyro_startup_error_count[INS_MAX_INSTANCES];
  464. bool _startup_error_counts_set;
  465. uint32_t _startup_ms;
  466. uint8_t imu_kill_mask;
  467. };
  468. namespace AP {
  469. AP_InertialSensor &ins();
  470. };