AP_InertialSensor_Backend.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_InertialSensor.h"
  3. #include "AP_InertialSensor_Backend.h"
  4. #include <AP_Logger/AP_Logger.h>
  5. #if AP_MODULE_SUPPORTED
  6. #include <AP_Module/AP_Module.h>
  7. #include <stdio.h>
  8. #endif
  9. #define SENSOR_RATE_DEBUG 0
  10. const extern AP_HAL::HAL& hal;
  11. AP_InertialSensor_Backend::AP_InertialSensor_Backend(AP_InertialSensor &imu) :
  12. _imu(imu)
  13. {
  14. }
  15. /*
  16. notify of a FIFO reset so we don't use bad data to update observed sensor rate
  17. */
  18. void AP_InertialSensor_Backend::notify_accel_fifo_reset(uint8_t instance)
  19. {
  20. _imu._sample_accel_count[instance] = 0;
  21. _imu._sample_accel_start_us[instance] = 0;
  22. }
  23. /*
  24. notify of a FIFO reset so we don't use bad data to update observed sensor rate
  25. */
  26. void AP_InertialSensor_Backend::notify_gyro_fifo_reset(uint8_t instance)
  27. {
  28. _imu._sample_gyro_count[instance] = 0;
  29. _imu._sample_gyro_start_us[instance] = 0;
  30. }
  31. // set the amount of oversamping a accel is doing
  32. void AP_InertialSensor_Backend::_set_accel_oversampling(uint8_t instance, uint8_t n)
  33. {
  34. _imu._accel_over_sampling[instance] = n;
  35. }
  36. // set the amount of oversamping a gyro is doing
  37. void AP_InertialSensor_Backend::_set_gyro_oversampling(uint8_t instance, uint8_t n)
  38. {
  39. _imu._gyro_over_sampling[instance] = n;
  40. }
  41. /*
  42. update the sensor rate for FIFO sensors
  43. FIFO sensors produce samples at a fixed rate, but the clock in the
  44. sensor may vary slightly from the system clock. This slowly adjusts
  45. the rate to the observed rate
  46. */
  47. void AP_InertialSensor_Backend::_update_sensor_rate(uint16_t &count, uint32_t &start_us, float &rate_hz) const
  48. {
  49. uint32_t now = AP_HAL::micros();
  50. if (start_us == 0) {
  51. count = 0;
  52. start_us = now;
  53. } else {
  54. count++;
  55. if (now - start_us > 1000000UL) {
  56. float observed_rate_hz = count * 1.0e6f / (now - start_us);
  57. #if SENSOR_RATE_DEBUG
  58. printf("RATE: %.1f should be %.1f\n", observed_rate_hz, rate_hz);
  59. #endif
  60. float filter_constant = 0.98f;
  61. float upper_limit = 1.05f;
  62. float lower_limit = 0.95f;
  63. if (sensors_converging()) {
  64. // converge quickly for first 30s, then more slowly
  65. filter_constant = 0.8f;
  66. upper_limit = 2.0f;
  67. lower_limit = 0.5f;
  68. }
  69. observed_rate_hz = constrain_float(observed_rate_hz, rate_hz*lower_limit, rate_hz*upper_limit);
  70. rate_hz = filter_constant * rate_hz + (1-filter_constant) * observed_rate_hz;
  71. count = 0;
  72. start_us = now;
  73. }
  74. }
  75. }
  76. void AP_InertialSensor_Backend::_rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
  77. {
  78. /*
  79. accel calibration is always done in sensor frame with this
  80. version of the code. That means we apply the rotation after the
  81. offsets and scaling.
  82. */
  83. // rotate for sensor orientation
  84. accel.rotate(_imu._accel_orientation[instance]);
  85. // apply offsets
  86. accel -= _imu._accel_offset[instance];
  87. // apply scaling
  88. const Vector3f &accel_scale = _imu._accel_scale[instance].get();
  89. accel.x *= accel_scale.x;
  90. accel.y *= accel_scale.y;
  91. accel.z *= accel_scale.z;
  92. // rotate to body frame
  93. if (_imu._board_orientation == ROTATION_CUSTOM && _imu._custom_rotation) {
  94. accel = *_imu._custom_rotation * accel;
  95. } else {
  96. accel.rotate(_imu._board_orientation);
  97. }
  98. }
  99. void AP_InertialSensor_Backend::_rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
  100. {
  101. // rotate for sensor orientation
  102. gyro.rotate(_imu._gyro_orientation[instance]);
  103. // gyro calibration is always assumed to have been done in sensor frame
  104. gyro -= _imu._gyro_offset[instance];
  105. if (_imu._board_orientation == ROTATION_CUSTOM && _imu._custom_rotation) {
  106. gyro = *_imu._custom_rotation * gyro;
  107. } else {
  108. gyro.rotate(_imu._board_orientation);
  109. }
  110. }
  111. /*
  112. rotate gyro vector and add the gyro offset
  113. */
  114. void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &gyro)
  115. {
  116. if ((1U<<instance) & _imu.imu_kill_mask) {
  117. return;
  118. }
  119. _imu._gyro[instance] = gyro;
  120. _imu._gyro_healthy[instance] = true;
  121. // publish delta angle
  122. _imu._delta_angle[instance] = _imu._delta_angle_acc[instance];
  123. _imu._delta_angle_dt[instance] = _imu._delta_angle_acc_dt[instance];
  124. _imu._delta_angle_valid[instance] = true;
  125. }
  126. void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
  127. const Vector3f &gyro,
  128. uint64_t sample_us)
  129. {
  130. if ((1U<<instance) & _imu.imu_kill_mask) {
  131. return;
  132. }
  133. float dt;
  134. _update_sensor_rate(_imu._sample_gyro_count[instance], _imu._sample_gyro_start_us[instance],
  135. _imu._gyro_raw_sample_rates[instance]);
  136. uint64_t last_sample_us = _imu._gyro_last_sample_us[instance];
  137. /*
  138. we have two classes of sensors. FIFO based sensors produce data
  139. at a very predictable overall rate, but the data comes in
  140. bunches, so we use the provided sample rate for deltaT. Non-FIFO
  141. sensors don't bunch up samples, but also tend to vary in actual
  142. rate, so we use the provided sample_us to get the deltaT. The
  143. difference between the two is whether sample_us is provided.
  144. */
  145. if (sample_us != 0 && _imu._gyro_last_sample_us[instance] != 0) {
  146. dt = (sample_us - _imu._gyro_last_sample_us[instance]) * 1.0e-6f;
  147. _imu._gyro_last_sample_us[instance] = sample_us;
  148. } else {
  149. // don't accept below 100Hz
  150. if (_imu._gyro_raw_sample_rates[instance] < 100) {
  151. return;
  152. }
  153. dt = 1.0f / _imu._gyro_raw_sample_rates[instance];
  154. _imu._gyro_last_sample_us[instance] = AP_HAL::micros64();
  155. }
  156. #if AP_MODULE_SUPPORTED
  157. // call gyro_sample hook if any
  158. AP_Module::call_hook_gyro_sample(instance, dt, gyro);
  159. #endif
  160. // push gyros if optical flow present
  161. if (hal.opticalflow) {
  162. hal.opticalflow->push_gyro(gyro.x, gyro.y, dt);
  163. }
  164. // compute delta angle
  165. Vector3f delta_angle = (gyro + _imu._last_raw_gyro[instance]) * 0.5f * dt;
  166. // compute coning correction
  167. // see page 26 of:
  168. // Tian et al (2010) Three-loop Integration of GPS and Strapdown INS with Coning and Sculling Compensation
  169. // Available: http://www.sage.unsw.edu.au/snap/publications/tian_etal2010b.pdf
  170. // see also examples/coning.py
  171. Vector3f delta_coning = (_imu._delta_angle_acc[instance] +
  172. _imu._last_delta_angle[instance] * (1.0f / 6.0f));
  173. delta_coning = delta_coning % delta_angle;
  174. delta_coning *= 0.5f;
  175. {
  176. WITH_SEMAPHORE(_sem);
  177. uint64_t now = AP_HAL::micros64();
  178. if (now - last_sample_us > 100000U) {
  179. // zero accumulator if sensor was unhealthy for 0.1s
  180. _imu._delta_angle_acc[instance].zero();
  181. _imu._delta_angle_acc_dt[instance] = 0;
  182. dt = 0;
  183. delta_angle.zero();
  184. }
  185. // integrate delta angle accumulator
  186. // the angles and coning corrections are accumulated separately in the
  187. // referenced paper, but in simulation little difference was found between
  188. // integrating together and integrating separately (see examples/coning.py)
  189. _imu._delta_angle_acc[instance] += delta_angle + delta_coning;
  190. _imu._delta_angle_acc_dt[instance] += dt;
  191. // save previous delta angle for coning correction
  192. _imu._last_delta_angle[instance] = delta_angle;
  193. _imu._last_raw_gyro[instance] = gyro;
  194. // apply the low pass filter
  195. Vector3f gyro_filtered = _imu._gyro_filter[instance].apply(gyro);
  196. // apply the notch filter
  197. if (_gyro_notch_enabled()) {
  198. gyro_filtered = _imu._gyro_notch_filter[instance].apply(gyro_filtered);
  199. }
  200. // apply the harmonic notch filter
  201. if (gyro_harmonic_notch_enabled()) {
  202. gyro_filtered = _imu._gyro_harmonic_notch_filter[instance].apply(gyro_filtered);
  203. }
  204. // if the filtering failed in any way then reset the filters and keep the old value
  205. if (gyro_filtered.is_nan() || gyro_filtered.is_inf()) {
  206. _imu._gyro_filter[instance].reset();
  207. _imu._gyro_notch_filter[instance].reset();
  208. _imu._gyro_harmonic_notch_filter[instance].reset();
  209. } else {
  210. _imu._gyro_filtered[instance] = gyro_filtered;
  211. }
  212. _imu._new_gyro_data[instance] = true;
  213. }
  214. if (!_imu.batchsampler.doing_post_filter_logging()) {
  215. log_gyro_raw(instance, sample_us, gyro);
  216. }
  217. else {
  218. log_gyro_raw(instance, sample_us, _imu._gyro_filtered[instance]);
  219. }
  220. }
  221. void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro)
  222. {
  223. AP_Logger *logger = AP_Logger::get_singleton();
  224. if (logger == nullptr) {
  225. // should not have been called
  226. return;
  227. }
  228. if (should_log_imu_raw()) {
  229. uint64_t now = AP_HAL::micros64();
  230. struct log_GYRO pkt = {
  231. LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+instance)),
  232. time_us : now,
  233. sample_us : sample_us?sample_us:now,
  234. GyrX : gyro.x,
  235. GyrY : gyro.y,
  236. GyrZ : gyro.z
  237. };
  238. logger->WriteBlock(&pkt, sizeof(pkt));
  239. } else {
  240. if (!_imu.batchsampler.doing_sensor_rate_logging()) {
  241. _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, gyro);
  242. }
  243. }
  244. }
  245. /*
  246. rotate accel vector, scale and add the accel offset
  247. */
  248. void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f &accel)
  249. {
  250. if ((1U<<instance) & _imu.imu_kill_mask) {
  251. return;
  252. }
  253. _imu._accel[instance] = accel;
  254. _imu._accel_healthy[instance] = true;
  255. // publish delta velocity
  256. _imu._delta_velocity[instance] = _imu._delta_velocity_acc[instance];
  257. _imu._delta_velocity_dt[instance] = _imu._delta_velocity_acc_dt[instance];
  258. _imu._delta_velocity_valid[instance] = true;
  259. if (_imu._accel_calibrator != nullptr && _imu._accel_calibrator[instance].get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
  260. Vector3f cal_sample = _imu._delta_velocity[instance];
  261. //remove rotation
  262. cal_sample.rotate_inverse(_imu._board_orientation);
  263. // remove scale factors
  264. const Vector3f &accel_scale = _imu._accel_scale[instance].get();
  265. cal_sample.x /= accel_scale.x;
  266. cal_sample.y /= accel_scale.y;
  267. cal_sample.z /= accel_scale.z;
  268. //remove offsets
  269. cal_sample += _imu._accel_offset[instance].get() * _imu._delta_velocity_dt[instance] ;
  270. _imu._accel_calibrator[instance].new_sample(cal_sample, _imu._delta_velocity_dt[instance]);
  271. }
  272. }
  273. void AP_InertialSensor_Backend::_notify_new_accel_raw_sample(uint8_t instance,
  274. const Vector3f &accel,
  275. uint64_t sample_us,
  276. bool fsync_set)
  277. {
  278. if ((1U<<instance) & _imu.imu_kill_mask) {
  279. return;
  280. }
  281. float dt;
  282. _update_sensor_rate(_imu._sample_accel_count[instance], _imu._sample_accel_start_us[instance],
  283. _imu._accel_raw_sample_rates[instance]);
  284. uint64_t last_sample_us = _imu._accel_last_sample_us[instance];
  285. /*
  286. we have two classes of sensors. FIFO based sensors produce data
  287. at a very predictable overall rate, but the data comes in
  288. bunches, so we use the provided sample rate for deltaT. Non-FIFO
  289. sensors don't bunch up samples, but also tend to vary in actual
  290. rate, so we use the provided sample_us to get the deltaT. The
  291. difference between the two is whether sample_us is provided.
  292. */
  293. if (sample_us != 0 && _imu._accel_last_sample_us[instance] != 0) {
  294. dt = (sample_us - _imu._accel_last_sample_us[instance]) * 1.0e-6f;
  295. _imu._accel_last_sample_us[instance] = sample_us;
  296. } else {
  297. // don't accept below 100Hz
  298. if (_imu._accel_raw_sample_rates[instance] < 100) {
  299. return;
  300. }
  301. dt = 1.0f / _imu._accel_raw_sample_rates[instance];
  302. _imu._accel_last_sample_us[instance] = AP_HAL::micros64();
  303. }
  304. #if AP_MODULE_SUPPORTED
  305. // call accel_sample hook if any
  306. AP_Module::call_hook_accel_sample(instance, dt, accel, fsync_set);
  307. #endif
  308. _imu.calc_vibration_and_clipping(instance, accel, dt);
  309. {
  310. WITH_SEMAPHORE(_sem);
  311. uint64_t now = AP_HAL::micros64();
  312. if (now - last_sample_us > 100000U) {
  313. // zero accumulator if sensor was unhealthy for 0.1s
  314. _imu._delta_velocity_acc[instance].zero();
  315. _imu._delta_velocity_acc_dt[instance] = 0;
  316. dt = 0;
  317. }
  318. // delta velocity
  319. _imu._delta_velocity_acc[instance] += accel * dt;
  320. _imu._delta_velocity_acc_dt[instance] += dt;
  321. _imu._accel_filtered[instance] = _imu._accel_filter[instance].apply(accel);
  322. if (_imu._accel_filtered[instance].is_nan() || _imu._accel_filtered[instance].is_inf()) {
  323. _imu._accel_filter[instance].reset();
  324. }
  325. _imu.set_accel_peak_hold(instance, _imu._accel_filtered[instance]);
  326. _imu._new_accel_data[instance] = true;
  327. }
  328. if (!_imu.batchsampler.doing_post_filter_logging()) {
  329. log_accel_raw(instance, sample_us, accel);
  330. } else {
  331. log_accel_raw(instance, sample_us, _imu._accel_filtered[instance]);
  332. }
  333. }
  334. void AP_InertialSensor_Backend::_notify_new_accel_sensor_rate_sample(uint8_t instance, const Vector3f &accel)
  335. {
  336. if (!_imu.batchsampler.doing_sensor_rate_logging()) {
  337. return;
  338. }
  339. _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, AP_HAL::micros64(), accel);
  340. }
  341. void AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(uint8_t instance, const Vector3f &gyro)
  342. {
  343. if (!_imu.batchsampler.doing_sensor_rate_logging()) {
  344. return;
  345. }
  346. _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, AP_HAL::micros64(), gyro);
  347. }
  348. void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel)
  349. {
  350. AP_Logger *logger = AP_Logger::get_singleton();
  351. if (logger == nullptr) {
  352. // should not have been called
  353. return;
  354. }
  355. if (should_log_imu_raw()) {
  356. uint64_t now = AP_HAL::micros64();
  357. struct log_ACCEL pkt = {
  358. LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ACC1_MSG+instance)),
  359. time_us : now,
  360. sample_us : sample_us?sample_us:now,
  361. AccX : accel.x,
  362. AccY : accel.y,
  363. AccZ : accel.z
  364. };
  365. logger->WriteBlock(&pkt, sizeof(pkt));
  366. } else {
  367. if (!_imu.batchsampler.doing_sensor_rate_logging()) {
  368. _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, sample_us, accel);
  369. }
  370. }
  371. }
  372. void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance,
  373. float max_offset)
  374. {
  375. _imu._accel_max_abs_offsets[instance] = max_offset;
  376. }
  377. // set accelerometer error_count
  378. void AP_InertialSensor_Backend::_set_accel_error_count(uint8_t instance, uint32_t error_count)
  379. {
  380. _imu._accel_error_count[instance] = error_count;
  381. }
  382. // set gyro error_count
  383. void AP_InertialSensor_Backend::_set_gyro_error_count(uint8_t instance, uint32_t error_count)
  384. {
  385. _imu._gyro_error_count[instance] = error_count;
  386. }
  387. // increment accelerometer error_count
  388. void AP_InertialSensor_Backend::_inc_accel_error_count(uint8_t instance)
  389. {
  390. _imu._accel_error_count[instance]++;
  391. }
  392. // increment gyro error_count
  393. void AP_InertialSensor_Backend::_inc_gyro_error_count(uint8_t instance)
  394. {
  395. _imu._gyro_error_count[instance]++;
  396. }
  397. // return the requested sample rate in Hz
  398. uint16_t AP_InertialSensor_Backend::get_sample_rate_hz(void) const
  399. {
  400. // enum can be directly cast to Hz
  401. return (uint16_t)_imu._sample_rate;
  402. }
  403. /*
  404. publish a temperature value for an instance
  405. */
  406. void AP_InertialSensor_Backend::_publish_temperature(uint8_t instance, float temperature)
  407. {
  408. if ((1U<<instance) & _imu.imu_kill_mask) {
  409. return;
  410. }
  411. _imu._temperature[instance] = temperature;
  412. /* give the temperature to the control loop in order to keep it constant*/
  413. if (instance == 0) {
  414. hal.util->set_imu_temp(temperature);
  415. }
  416. }
  417. /*
  418. common gyro update function for all backends
  419. */
  420. void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
  421. {
  422. WITH_SEMAPHORE(_sem);
  423. if ((1U<<instance) & _imu.imu_kill_mask) {
  424. return;
  425. }
  426. if (_imu._new_gyro_data[instance]) {
  427. _publish_gyro(instance, _imu._gyro_filtered[instance]);
  428. _imu._new_gyro_data[instance] = false;
  429. }
  430. // possibly update filter frequency
  431. if (_last_gyro_filter_hz != _gyro_filter_cutoff() || sensors_converging()) {
  432. _imu._gyro_filter[instance].set_cutoff_frequency(_gyro_raw_sample_rate(instance), _gyro_filter_cutoff());
  433. _last_gyro_filter_hz = _gyro_filter_cutoff();
  434. }
  435. // possily update the harmonic notch filter parameters
  436. if (!is_equal(_last_harmonic_notch_bandwidth_hz, gyro_harmonic_notch_bandwidth_hz()) ||
  437. !is_equal(_last_harmonic_notch_attenuation_dB, gyro_harmonic_notch_attenuation_dB()) ||
  438. sensors_converging()) {
  439. _imu._gyro_harmonic_notch_filter[instance].init(_gyro_raw_sample_rate(instance), gyro_harmonic_notch_center_freq_hz(), gyro_harmonic_notch_bandwidth_hz(), gyro_harmonic_notch_attenuation_dB());
  440. _last_harmonic_notch_center_freq_hz = gyro_harmonic_notch_center_freq_hz();
  441. _last_harmonic_notch_bandwidth_hz = gyro_harmonic_notch_bandwidth_hz();
  442. _last_harmonic_notch_attenuation_dB = gyro_harmonic_notch_attenuation_dB();
  443. } else if (!is_equal(_last_harmonic_notch_center_freq_hz, gyro_harmonic_notch_center_freq_hz())) {
  444. _imu._gyro_harmonic_notch_filter[instance].update(gyro_harmonic_notch_center_freq_hz());
  445. _last_harmonic_notch_center_freq_hz = gyro_harmonic_notch_center_freq_hz();
  446. }
  447. // possily update the notch filter parameters
  448. if (!is_equal(_last_notch_center_freq_hz, _gyro_notch_center_freq_hz()) ||
  449. !is_equal(_last_notch_bandwidth_hz, _gyro_notch_bandwidth_hz()) ||
  450. !is_equal(_last_notch_attenuation_dB, _gyro_notch_attenuation_dB()) ||
  451. sensors_converging()) {
  452. _imu._gyro_notch_filter[instance].init(_gyro_raw_sample_rate(instance), _gyro_notch_center_freq_hz(), _gyro_notch_bandwidth_hz(), _gyro_notch_attenuation_dB());
  453. _last_notch_center_freq_hz = _gyro_notch_center_freq_hz();
  454. _last_notch_bandwidth_hz = _gyro_notch_bandwidth_hz();
  455. _last_notch_attenuation_dB = _gyro_notch_attenuation_dB();
  456. }
  457. }
  458. /*
  459. common accel update function for all backends
  460. */
  461. void AP_InertialSensor_Backend::update_accel(uint8_t instance)
  462. {
  463. WITH_SEMAPHORE(_sem);
  464. if ((1U<<instance) & _imu.imu_kill_mask) {
  465. return;
  466. }
  467. if (_imu._new_accel_data[instance]) {
  468. _publish_accel(instance, _imu._accel_filtered[instance]);
  469. _imu._new_accel_data[instance] = false;
  470. }
  471. // possibly update filter frequency
  472. if (_last_accel_filter_hz != _accel_filter_cutoff()) {
  473. _imu._accel_filter[instance].set_cutoff_frequency(_accel_raw_sample_rate(instance), _accel_filter_cutoff());
  474. _last_accel_filter_hz = _accel_filter_cutoff();
  475. }
  476. }
  477. bool AP_InertialSensor_Backend::should_log_imu_raw() const
  478. {
  479. if (_imu._log_raw_bit == (uint32_t)-1) {
  480. // tracker does not set a bit
  481. return false;
  482. }
  483. const AP_Logger *logger = AP_Logger::get_singleton();
  484. if (logger == nullptr) {
  485. return false;
  486. }
  487. if (!logger->should_log(_imu._log_raw_bit)) {
  488. return false;
  489. }
  490. return true;
  491. }