APM:Libraries
AP_InertialSensor_Revo.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14 */
15 /*
16  copied from AP_InertialSensor_Invensense, removed aux bus and FIFO usage
17  this driver can be common Invensense driver for boards with connected DataReady pin if HAL API will be extended
18  to support IO_Complete callbacks
19 
20  driver for all supported Invensense IMUs, including MPU6000, MPU9250
21  ICM-20608 and ICM-20602
22  */
23 
24 
25 #include <AP_HAL/AP_HAL.h>
26 
27 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(INVENSENSE_DRDY_PIN)
28 
29 #include <assert.h>
30 #include <utility>
31 #include <stdio.h>
32 #include <AP_HAL/Util.h>
33 
34 #include <AP_HAL_F4Light/GPIO.h>
38 
39 #include "AP_InertialSensor_Revo.h"
41 
42 extern const AP_HAL::HAL& hal;
43 
44 #define debug(fmt, args ...) do {printf("MPU: " fmt "\n", ## args); } while(0)
45 
46 /*
47  EXT_SYNC allows for frame synchronisation with an external device
48  such as a camera. When enabled the LSB of AccelZ holds the FSYNC bit
49  */
50 #ifndef INVENSENSE_EXT_SYNC_ENABLE
51 #define INVENSENSE_EXT_SYNC_ENABLE 0
52 #endif
53 
54 
55 #define MPU_SAMPLE_SIZE 14
56 #define MPU_FIFO_DOWNSAMPLE_COUNT 8
57 #define MPU_FIFO_BUFFER_LEN 64// ms of samples
58 
59 #define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]))
60 #define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])
61 
62 /*
63  * RM-MPU-6000A-00.pdf, page 33, section 4.25 lists LSB sensitivity of
64  * gyro as 16.4 LSB/DPS at scale factor of +/- 2000dps (FS_SEL==3)
65  */
66 static const float GYRO_SCALE = (0.0174532f / 16.4f);
67 
68 #ifdef MPU_DEBUG_LOG
69  mpu_log_item AP_InertialSensor_Revo::mpu_log[MPU_LOG_SIZE] IN_CCM;
70  uint16_t AP_InertialSensor_Revo::mpu_log_ptr=0;
71 #endif
72 
73 /*
74  * RM-MPU-6000A-00.pdf, page 31, section 4.23 lists LSB sensitivity of
75  * accel as 4096 LSB/mg at scale factor of +/- 8g (AFS_SEL==2)
76  *
77  * See note below about accel scaling of engineering sample MPU6k
78  * variants however
79  */
80 
83  enum Rotation rotation)
85  , _temp_filter(1000, 1)
86  , _rotation(rotation)
87  , _dev(std::move(dev))
88  , nodata_count(0)
89  , accel_len(0)
90 {
91 }
92 
94 {
95  if (_fifo_buffer != nullptr) {
97  }
98 }
99 
102  enum Rotation rotation)
103 {
104  return nullptr;
105 }
106 
107 
110  enum Rotation rotation)
111 {
112  if (!dev) {
113  return nullptr;
114  }
115  AP_InertialSensor_Revo *sensor;
116 
117  dev->set_read_flag(0x80);
118 
119  sensor = new AP_InertialSensor_Revo(imu, std::move(dev), rotation);
120  if (!sensor || !sensor->_init()) {
121  delete sensor;
122  return nullptr;
123  }
124  if (sensor->_mpu_type == Invensense_MPU9250) {
125  sensor->_id = HAL_INS_MPU9250_SPI;
126  } else if (sensor->_mpu_type == Invensense_MPU6500) {
127  sensor->_id = HAL_INS_MPU6500;
128  } else {
129  sensor->_id = HAL_INS_MPU60XX_SPI;
130  }
131 
132  return sensor;
133 }
134 
136 {
137  _drdy_pin = hal.gpio->channel(INVENSENSE_DRDY_PIN);
138  _drdy_pin->mode(INPUT_PULLDOWN);
139 
140  bool success = _hardware_init();
141 
142  return success;
143 }
144 
145 
147  // initially run the bus at low speed
148  _dev->set_speed(AP_HAL::Device::SPEED_LOW);
149 
150  // setup ODR and on-sensor filtering
151  _set_filter_register();
152 
153  // set sample rate to 1000Hz and apply a software filter
154  // In this configuration, the gyro sample rate is 8kHz
155  _register_write(MPUREG_SMPLRT_DIV, 0, true);
156  hal.scheduler->delay_microseconds(10);
157 
158  // Gyro scale 2000ยบ/s
159  _register_write(MPUREG_GYRO_CONFIG, BITS_GYRO_FS_2000DPS, true);
160  hal.scheduler->delay_microseconds(10);
161 
162 
163  if (_mpu_type == Invensense_MPU6000 &&
164  ((product_id == MPU6000ES_REV_C4) ||
165  (product_id == MPU6000ES_REV_C5) ||
166  (product_id == MPU6000_REV_C4) ||
167  (product_id == MPU6000_REV_C5))) {
168  // Accel scale 8g (4096 LSB/g)
169  // Rev C has different scaling than rev D
170  _register_write(MPUREG_ACCEL_CONFIG,1<<3, true);
171  _accel_scale = GRAVITY_MSS / 4096.f;
172  } else {
173  // Accel scale 16g (2048 LSB/g)
174  _register_write(MPUREG_ACCEL_CONFIG,3<<3, true);
175  _accel_scale = GRAVITY_MSS / 2048.f;
176  }
177  hal.scheduler->delay_microseconds(10);
178 
179  if (_mpu_type == Invensense_ICM20608 ||
180  _mpu_type == Invensense_ICM20602) {
181  // this avoids a sensor bug, see description above
182  _register_write(MPUREG_ICM_UNDOC1, MPUREG_ICM_UNDOC1_VALUE, true);
183  }
184 
185  // configure interrupt to fire when new data arrives
186  _register_write(MPUREG_INT_ENABLE, BIT_RAW_RDY_EN);
187  hal.scheduler->delay_microseconds(10);
188 
189  // clear interrupt on any read, and hold the data ready pin high
190  // until we clear the interrupt
191  _register_write(MPUREG_INT_PIN_CFG, _register_read(MPUREG_INT_PIN_CFG) | BIT_INT_RD_CLEAR | BIT_LATCH_INT_EN);
192 
193  // now that we have initialised, we set the bus speed to high
194  _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
195 }
196 
198 {
199  if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
200  return;
201  }
202 
203  // initially run the bus at low speed
204  _dev->set_speed(AP_HAL::Device::SPEED_LOW);
205 
206  // only used for wake-up in accelerometer only low power mode
207  _register_write(MPUREG_PWR_MGMT_2, 0x00);
208  hal.scheduler->delay(1);
209 
210  // never use buggy FIFO
211 // _fifo_reset();
212 
213  // grab the used instances
214  enum DevTypes gdev, adev;
215  switch (_mpu_type) {
216  case Invensense_MPU9250:
217  gdev = DEVTYPE_GYR_MPU9250;
218  adev = DEVTYPE_ACC_MPU9250;
219  break;
220  case Invensense_MPU6000:
221  case Invensense_MPU6500:
222  case Invensense_ICM20608:
223  case Invensense_ICM20602:
224  default:
225  gdev = DEVTYPE_GYR_MPU6000;
226  adev = DEVTYPE_ACC_MPU6000;
227  break;
228  }
229 
230  /*
231  setup temperature sensitivity and offset. This varies
232  considerably between parts
233  */
234  switch (_mpu_type) {
235  case Invensense_MPU9250:
236  temp_zero = 21;
237  temp_sensitivity = 1.0/340;
238  break;
239 
240  case Invensense_MPU6000:
241  case Invensense_MPU6500:
242  temp_zero = 36.53;
243  temp_sensitivity = 1.0/340;
244  break;
245 
246  case Invensense_ICM20608:
247  case Invensense_ICM20602:
248  temp_zero = 25;
249  temp_sensitivity = 1.0/326.8;
250  break;
251  }
252 
253  _gyro_instance = _imu.register_gyro(1000, _dev->get_bus_id_devtype(gdev));
254  _accel_instance = _imu.register_accel(1000, _dev->get_bus_id_devtype(adev));
255 
256  // read and remember the product ID rev c has 1/2 the sensitivity of rev d
257  product_id = _register_read(MPUREG_PRODUCT_ID);
258 
259  _start(); // start MPU
260 
261  _dev->get_semaphore()->give();
262 
263  // setup sensor rotations from probe()
266 
267  // allocate fifo buffer
268  _fifo_buffer = (uint8_t *)(hal.util->malloc_type((MPU_FIFO_BUFFER_LEN+1) * MPU_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE));
269  if (_fifo_buffer == nullptr) {
270  AP_HAL::panic("Invensense: Unable to allocate FIFO buffer");
271  }
272 
273  GPIO::_attach_interrupt(INVENSENSE_DRDY_PIN, Scheduler::get_handler(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Revo::_isr, void)), RISING, MPU_INT_PRIORITY);
274 
275  _register_read(MPUREG_INT_STATUS); // reset interrupt request
276 
277  // some longer than MPU period
278  task_handle = Scheduler::register_timer_task(1010, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Revo::_poll_data, void), NULL); // period just for case, task will be activated by request
279 // REVOMINIScheduler::set_task_priority(task_handle, DRIVER_PRIORITY); // like other drivers
280 }
281 
282 
283 /*
284  publish any pending data
285  */
287 {
290 
291  _publish_temperature(_accel_instance, _temp_filtered);
292 
293  return true;
294 }
295 
296 /*
297  accumulate new samples
298  */
300 {
301  // nothing to do
302 }
303 
304 
305 /*
306  * Return true if the Invensense has new data available for reading.
307  *
308  * We use the data ready pin if it is available. Otherwise, read the
309  * status register.
310  */
312 {
313  return _drdy_pin->read() != 0;
314 }
315 
316 /*
317  ISR procedure for data read. Ring buffer don't needs to use semaphores for data access
318 
319  also we don't own a bus semaphore and can't guarantee that bus is free. But in Revo MPU uses personal SPI bus so it is ABSOLUTELY free :)
320 */
322  uint8_t *data = _fifo_buffer + MPU_SAMPLE_SIZE * write_ptr;
323 // _fifo_buffer[write_ptr].time = REVOMINIScheduler::_micros64();
324 
325  _dev->register_completion_callback(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Revo::_ioc, void)); // IO completion interrupt
326 
327  _block_read(MPUREG_ACCEL_XOUT_H, data, MPU_SAMPLE_SIZE); // start SPI transfer
328 }
329 
330 void AP_InertialSensor_Revo::_ioc(){ // io completion ISR, data already in its place
331  uint16_t new_wp = write_ptr+1;
332  if(new_wp >= MPU_FIFO_BUFFER_LEN) { // move write pointer
333  new_wp=0; // ring
334  }
335  if(new_wp == read_ptr) { // buffer overflow
336 #ifdef MPU_DEBUG
337  REVOMINIScheduler::MPU_buffer_overflow(); // count them
338  // not overwrite, just skip last data
339 #endif
340  } else {
341  write_ptr=new_wp; // move forward
342  }
343 
344  //_dev->register_completion_callback(NULL);
345 // we should release the bus semaphore if we use them
346 // _dev->get_semaphore()->give(); // release
347 
348 
349  if(Scheduler::get_current_task() != (void *)task_handle) {
350 /*
351  REVOMINIScheduler::set_task_active(task_handle); // resume task instead of using period.
352  REVOMINIScheduler::context_switch_isr(); // and reschedule tasks after interrupt
353 */
354  Scheduler::task_resume(task_handle); // resume task instead of using period.
355  }
356 }
357 
358 /*
359  * Timer process to poll for new data from the Invensense. Called from timer's interrupt or from personal thread
360  */
362 {
363  _read_fifo();
364 }
365 
366 bool AP_InertialSensor_Revo::_accumulate(uint8_t *samples, uint8_t n_samples)
367 {
368  bool ret=true;
369  for (uint8_t i = 0; i < n_samples; i++) {
370  const uint8_t *data = samples + MPU_SAMPLE_SIZE * i;
371  Vector3f accel, gyro;
372  bool fsync_set = false;
373 
374 
375  accel = Vector3f(int16_val(data, 1),
376  int16_val(data, 0),
377  -int16_val(data, 2)) * _accel_scale;
378 
379  int16_t t2 = int16_val(data, 3);
380 /*
381  if (!_check_raw_temp(t2)) {
382  debug("temp reset %d %d i=%d", _raw_temp, t2, i);
383  return false; // just skip this sample
384  }
385 */
386  float temp = t2 * temp_sensitivity + temp_zero;
387 
388  gyro = Vector3f(int16_val(data, 5),
389  int16_val(data, 4),
390  -int16_val(data, 6)) * GYRO_SCALE;
391 
394 
395 #if 0 // filter out samples if vector length changed by 100% This is cool for debug but drops samples in the case of even weak blows
396 
397 #define FILTER_KOEF 0.1
398  float len = accel.length();
399  if(is_zero(accel_len)) {
400  accel_len=len;
401  } else {
402  float d = abs(accel_len-len)/(accel_len+len);
403  if(d*100 > 50) { // difference more than 100% from mean value
404  debug("accel len error: mean %f got %f", accel_len, len );
405  ret= false; //just report
406  float k = FILTER_KOEF / (d*10); // 5 and more, so one bad sample never change mean more than 4%
407  accel_len = accel_len * (1-k) + len*k; // complimentary filter 1/k on bad samples
408  } else {
409  accel_len = accel_len * (1-FILTER_KOEF) + len*FILTER_KOEF; // complimentary filter 1/10 on good samples
410  }
411  }
412 #endif
413 
414  if(ret) {
415  uint8_t kG = hal_param_helper->_correct_gyro;
416  if(kG){ // compensate gyro drift by long-time mean
417  float gyro_koef = 1.0 / (kG * 1000); // integrator time constant in seconds
418  gyro_mean = gyro_mean * (1-gyro_koef) + gyro*gyro_koef;
419 
420  gyro -= gyro_mean;
421  }
422 
423  _notify_new_accel_raw_sample(_accel_instance, accel, 0, fsync_set);
425 
426  _temp_filtered = _temp_filter.apply(temp);
427  }
428  }
429  return ret;
430 }
431 
432 /*
433  when doing sensor-rate sampling the sensor gives us 8k samples/second. Every 2nd accel sample is a duplicate.
434 
435  To filter this we first apply a 1p low pass filter at 188Hz, then we
436  average over 8 samples to bring the data rate down to 1kHz. This
437  gives very good aliasing rejection at frequencies well above what
438  can be handled with 1kHz sample rates.
439  */
440 bool AP_InertialSensor_Revo::_accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
441 {
442  int32_t tsum = 0;
443  const int32_t clip_limit = AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS / _accel_scale;
444  bool clipped = false;
445  bool ret = true;
446 
447  for (uint8_t i = 0; i < n_samples; i++) {
448  const uint8_t *data = samples + MPU_SAMPLE_SIZE * i;
449 
450  // use temperatue to detect FIFO corruption
451  int16_t t2 = int16_val(data, 3);
452 /* MPU don't likes such reads
453  if (!_check_raw_temp(t2)) {
454  debug("temp reset %d %d", _raw_temp, t2);
455 // _fifo_reset();
456  ret = false;
457  break;
458  }
459 */
460  tsum += t2;
461 
462  if ((_accum.count & 1) == 0) {
463  // accel data is at 4kHz
464  Vector3f a(int16_val(data, 1),
465  int16_val(data, 0),
466  -int16_val(data, 2));
467  if (fabsf(a.x) > clip_limit ||
468  fabsf(a.y) > clip_limit ||
469  fabsf(a.z) > clip_limit) {
470  clipped = true;
471  }
472  _accum.accel += _accum.accel_filter.apply(a);
473  }
474 
475  Vector3f g(int16_val(data, 5),
476  int16_val(data, 4),
477  -int16_val(data, 6));
478 
479  _accum.gyro += _accum.gyro_filter.apply(g);
480  _accum.count++;
481 
482  if (_accum.count == MPU_FIFO_DOWNSAMPLE_COUNT) {
483  float ascale = _accel_scale / (MPU_FIFO_DOWNSAMPLE_COUNT/2);
484  _accum.accel *= ascale;
485 
486  float gscale = GYRO_SCALE / MPU_FIFO_DOWNSAMPLE_COUNT;
487  _accum.gyro *= gscale;
488 
491 
492  _notify_new_accel_raw_sample(_accel_instance, _accum.accel, 0, false);
494 
495  _accum.accel.zero();
496  _accum.gyro.zero();
497  _accum.count = 0;
498  }
499  }
500 
501  if (clipped) {
503  }
504 
505  if (ret) {
506  float temp = (static_cast<float>(tsum)/n_samples)*temp_sensitivity + temp_zero;
507  _temp_filtered = _temp_filter.apply(temp);
508  }
509 
510  return ret;
511 }
512 
513 
514 #define MAX_NODATA_TIME 5000 // 5ms
515 
517 {
518  uint32_t now=Scheduler::_micros();
519 
520 #ifdef MPU_DEBUG_LOG
521  uint16_t old_log_ptr=mpu_log_ptr;
522  mpu_log_item & p = mpu_log[mpu_log_ptr++];
523  if(mpu_log_ptr>=MPU_LOG_SIZE) mpu_log_ptr=0;
524  p.t=now;
525  p.read_ptr=read_ptr;
526  p.write_ptr=write_ptr;
527 #endif
528 
529  if(read_ptr == write_ptr) {
530  if(_data_ready()){ // no interrupt for some reason?
531  _isr();
532  }
533  if(now - last_sample > MAX_NODATA_TIME) { // something went wrong - data stream stopped
534  _start(); // try to restart MPU
535  last_sample=now;
536 #ifdef MPU_DEBUG
537  REVOMINIScheduler::MPU_restarted(); // count them
538 #endif
539  }
540  return;
541  }
542 
543  last_sample=now;
544 
545  uint16_t count = 0;
546 #ifdef MPU_DEBUG
547  uint32_t dt = 0;
548  uint32_t t = now;
549 #endif
550 
551  while(read_ptr != write_ptr) { // there are samples
552 // uint64_t time = _fifo_buffer[read_ptr++].time; // we can get exact time
553  uint8_t *rx = _fifo_buffer + MPU_SAMPLE_SIZE * read_ptr++; // calculate address and move to next item
554  if(read_ptr >= MPU_FIFO_BUFFER_LEN) { // move write pointer
555  read_ptr=0; // ring
556  }
557 
558 
559  if (_fast_sampling) {
560  if (!_accumulate_sensor_rate_sampling(rx, 1)) {
561 // debug("stop at %u of %u", n_samples, bytes_read/MPU_SAMPLE_SIZE);
562  // break; don't break before all items in queue will be readed
563  continue;
564  }
565  } else {
566  if (!_accumulate(rx, 1)) {
567  // break; don't break before all items in queue will be readed
568  continue;
569  }
570  }
571  count++;
572  }
573  now = Scheduler::_micros();
574  last_sample=now;
575 
576 #ifdef MPU_DEBUG_LOG
577  if(count==1) {
578  mpu_log_ptr = old_log_ptr;
579  }
580 #endif
581 #ifdef MPU_DEBUG
582  dt= now - t;// time from entry
583  REVOMINIScheduler::MPU_stats(count,dt);
584 #endif
585 
586 // only wait_for_sample() uses delay_microseconds_boost() so
587 // resume main thread then it waits for this sample - sample already got
588  Scheduler::resume_boost();
589 }
590 
591 /*
592  fetch temperature in order to detect FIFO sync errors
593 */
595 {
596  if (abs(t2 - _raw_temp) < 400) {
597  // cached copy OK
598  return true;
599  }
600  uint8_t trx[2];
601  if (_block_read(MPUREG_TEMP_OUT_H, trx, 2)) {
602  _raw_temp = int16_val(trx, 0);
603  }
604  return (abs(t2 - _raw_temp) < 400);
605 }
606 
607 bool AP_InertialSensor_Revo::_block_read(uint8_t reg, uint8_t *buf,
608  uint32_t size)
609 {
610  return _dev->read_registers(reg, buf, size);
611 }
612 
613 uint8_t AP_InertialSensor_Revo::_register_read(uint8_t reg)
614 {
615  uint8_t val = 0;
616  _dev->read_registers(reg, &val, 1);
617  return val;
618 }
619 
620 void AP_InertialSensor_Revo::_register_write(uint8_t reg, uint8_t val, bool checked)
621 {
622  _dev->write_register(reg, val, checked);
623 }
624 
625 /*
626  set the DLPF filter frequency. Assumes caller has taken semaphore
627  */
629 {
630  uint8_t config;
631 
632 #if INVENSENSE_EXT_SYNC_ENABLE
633  // add in EXT_SYNC bit if enabled
635 #else
636  config = 0;
637 #endif
638 
640  _fast_sampling = (_mpu_type != Invensense_MPU6000 && _dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI);
641  if (_fast_sampling) {
642 #ifdef DEBUG_BUILD
643  printf("MPU[%u]: enabled fast sampling\n", _accel_instance);
644 #endif
645  // for logging purposes set the oversamping rate
646  _set_accel_oversampling(_accel_instance, MPU_FIFO_DOWNSAMPLE_COUNT/2);
647  _set_gyro_oversampling(_gyro_instance, MPU_FIFO_DOWNSAMPLE_COUNT);
648 
649  /* set divider for internal sample rate to 0x1F when fast
650  sampling enabled. This reduces the impact of the slave
651  sensor on the sample rate. It ends up with around 75Hz
652  slave rate, and reduces the impact on the gyro and accel
653  sample rate, ending up with around 7760Hz gyro rate and
654  3880Hz accel rate
655  */
656  _register_write(MPUREG_I2C_SLV4_CTRL, 0x1F);
657  }
658  }
659 
660  if (_fast_sampling) {
661  // this gives us 8kHz sampling on gyros and 4kHz on accels
662  config |= BITS_DLPF_CFG_256HZ_NOLPF2;
663  } else {
664  // limit to 1kHz if not on SPI
665  config |= BITS_DLPF_CFG_188HZ;
666  }
667 
669  _register_write(MPUREG_CONFIG, config, true);
670 
671  if (_mpu_type != Invensense_MPU6000) {
672  if (_fast_sampling) {
673  // setup for 4kHz accels
674  _register_write(ICMREG_ACCEL_CONFIG2, ICM_ACC_FCHOICE_B, true);
675  } else {
676  _register_write(ICMREG_ACCEL_CONFIG2, ICM_ACC_DLPF_CFG_218HZ, true);
677  }
678  }
679 }
680 
681 /*
682  check whoami for sensor type
683  */
685 {
686  uint8_t whoami = _register_read(MPUREG_WHOAMI);
687  switch (whoami) {
688  case MPU_WHOAMI_6000:
689  _mpu_type = Invensense_MPU6000;
690  return true;
691  case MPU_WHOAMI_6500:
692  _mpu_type = Invensense_MPU6500;
693  return true;
694  case MPU_WHOAMI_MPU9250:
695  case MPU_WHOAMI_MPU9255:
696  _mpu_type = Invensense_MPU9250;
697  return true;
698  case MPU_WHOAMI_20608:
699  _mpu_type = Invensense_ICM20608;
700  return true;
701  case MPU_WHOAMI_20602:
702  _mpu_type = Invensense_ICM20602;
703  return true;
704  }
705  // not a value WHOAMI result
706  return false;
707 }
708 
709 
711 {
712  if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
713  return false;
714  }
715 
716  // setup for register checking
717  _dev->setup_checked_registers(7, 20);
718 
719  // initially run the bus at low speed
720  _dev->set_speed(AP_HAL::Device::SPEED_LOW);
721 
722  if (!_check_whoami()) {
723  _dev->get_semaphore()->give();
724  return false;
725  }
726 
727  // Chip reset
728  uint8_t tries;
729  for (tries = 0; tries < 5; tries++) {
730  _last_stat_user_ctrl = _register_read(MPUREG_USER_CTRL);
731 
732  /* First disable the master I2C to avoid hanging the slaves on the
733  * aulixiliar I2C bus - it will be enabled again if the AuxiliaryBus
734  * is used */
735  if (_last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN) {
736  _last_stat_user_ctrl &= ~BIT_USER_CTRL_I2C_MST_EN;
737  _register_write(MPUREG_USER_CTRL, _last_stat_user_ctrl);
738  hal.scheduler->delay(10);
739  }
740 
741  /* reset device */
743  hal.scheduler->delay(100);
744 
745  /* bus-dependent initialization */
746  if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
747  /* Disable I2C bus if SPI selected (Recommended in Datasheet to be
748  * done just after the device is reset) */
749  _last_stat_user_ctrl |= BIT_USER_CTRL_I2C_IF_DIS;
750  _register_write(MPUREG_USER_CTRL, _last_stat_user_ctrl);
751  }
752 
753  /* bus-dependent initialization */
754  if ((_dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C) && (_mpu_type == Invensense_MPU9250)) {
755  /* Enable I2C bypass to access internal AK8963 */
756  _register_write(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);
757  }
758 
759  // Wake up device and select GyroZ clock. Note that the
760  // Invensense starts up in sleep mode, and it can take some time
761  // for it to come out of sleep
763  hal.scheduler->delay(5);
764 
765  // check it has woken up
766  if (_register_read(MPUREG_PWR_MGMT_1) == BIT_PWR_MGMT_1_CLK_ZGYRO) {
767  break;
768  }
769 
770  hal.scheduler->delay(10);
771  if (_data_ready()) {
772  break;
773  }
774  }
775 
776  _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
777  _dev->get_semaphore()->give();
778 
779  if (tries == 5) {
780 #ifdef DEBUG_BUILD
781  printf("Failed to boot Invensense 5 times\n");
782 #endif
783  return false;
784  }
785 
786  if (_mpu_type == Invensense_ICM20608 ||
787  _mpu_type == Invensense_ICM20602) {
788  // this avoids a sensor bug, see description above
789  _register_write(MPUREG_ICM_UNDOC1, MPUREG_ICM_UNDOC1_VALUE, true);
790  }
791 
792  return true;
793 }
794 
795 
796 #endif // BOARD_REVO
t2
Definition: calcH_MAG.c:1
#define BIT_LATCH_INT_EN
Definition: ICM20789.cpp:26
int printf(const char *fmt,...)
Definition: stdio.c:113
#define HAL_INS_MPU60XX_SPI
Definition: AP_HAL_Boards.h:79
#define BIT_INT_RD_CLEAR
Definition: ICM20789.cpp:25
#define BIT_BYPASS_EN
Definition: ICM20789.cpp:24
void set_gyro_orientation(uint8_t instance, enum Rotation rotation)
#define MPU_INT_PRIORITY
Definition: Config.h:48
Vector3< float > Vector3f
Definition: vector3.h:246
#define HAL_INS_MPU9250_SPI
Definition: AP_HAL_Boards.h:85
#define MPUREG_INT_PIN_CFG
Definition: ICM20789.cpp:23
uint8_t _gyro_instance[INS_MAX_INSTANCES]
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
#define MPU_FIFO_BUFFER_LEN
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define BIT_USER_CTRL_I2C_MST_EN
Definition: ICM20789.cpp:28
bool _check_raw_temp(int16_t t2)
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
virtual T apply(T sample)
Definition: AverageFilter.h:79
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
bool enable_fast_sampling(uint8_t instance)
AP_InertialSensor_Revo(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation)
#define MPUREG_WHOAMI
Definition: ICM20789.cpp:19
Rotation
Definition: rotations.h:27
#define HAL_INS_MPU6500
Definition: AP_HAL_Boards.h:92
bool update() override
void _set_gyro_oversampling(uint8_t instance, uint8_t n)
virtual void free_type(void *ptr, size_t size, Memory_Type mem_type)
Definition: Util.h:116
void _set_filter_register(void)
#define BIT_USER_CTRL_I2C_IF_DIS
Definition: ICM20789.cpp:30
void _register_write(uint8_t reg, uint8_t val, bool checked=false)
Definition: GPIO.h:100
#define debug(fmt, args ...)
enum Invensense_Type _mpu_type
#define MPUREG_CONFIG_EXT_SYNC_SHIFT
virtual void mode(uint8_t output)=0
virtual void delay(uint16_t ms)=0
#define BIT_PWR_MGMT_1_CLK_ZGYRO
Definition: ICM20789.cpp:32
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
uint8_t _accel_instance[INS_MAX_INSTANCES]
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static void * task_handle
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define MPU_WHOAMI_MPU9250
void increment_clip_count(uint8_t instance)
#define IN_CCM
Definition: AP_HAL_F4Light.h:9
virtual ~AP_InertialSensor_Revo()
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
#define int16_val(v, idx)
#define MPU_SAMPLE_SIZE
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
AverageFilterUInt16_Size4 _temp_filter
Definition: Filter.cpp:23
#define INVENSENSE_DRDY_PIN
Definition: f4light.h:27
static constexpr float FILTER_KOEF
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
#define NULL
Definition: hal_types.h:59
#define MPUREG_PWR_MGMT_1
Definition: ICM20789.cpp:21
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
float length(void) const
Definition: vector3.cpp:288
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
void _publish_temperature(uint8_t instance, float temperature)
uint8_t _register_read(uint8_t reg)
void set_read_flag(uint8_t flag)
Definition: Device.h:221
void set_accel_orientation(uint8_t instance, enum Rotation rotation)
AP_HAL::GPIO * gpio
Definition: HAL.h:111
virtual void delay_microseconds(uint16_t us)=0
void _set_accel_oversampling(uint8_t instance, uint8_t n)
bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool _accumulate(uint8_t *samples, uint8_t n_samples)
void accumulate() override
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void start() override
static const float GYRO_SCALE
#define BIT_PWR_MGMT_1_DEVICE_RESET
Definition: ICM20789.cpp:29
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
#define MPUREG_CONFIG_FIFO_MODE_STOP
#define AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define MPUREG_USER_CTRL
Definition: ICM20789.cpp:20