APM:Libraries
AP_InertialSensor_Invensense.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  driver for all supported Invensense IMUs, including MPU6000, MPU9250
17  ICM-20608 and ICM-20602
18  */
19 
20 #include <assert.h>
21 #include <utility>
22 #include <stdio.h>
23 
24 #include <AP_HAL/AP_HAL.h>
25 
27 
28 extern const AP_HAL::HAL& hal;
29 
30 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
31 #include <AP_HAL_Linux/GPIO.h>
32 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
33 #define INVENSENSE_DRDY_PIN BBB_P8_14
34 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
35 #define INVENSENSE_DRDY_PIN MINNOW_GPIO_I2S_CLK
36 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
37 #define INVENSENSE_EXT_SYNC_ENABLE 1
38 #endif
39 #endif
40 
41 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
42 // hal.console can be accessed from bus threads on ChibiOS
43 #define debug(fmt, args ...) do {hal.console->printf("MPU: " fmt "\n", ## args); } while(0)
44 #else
45 #define debug(fmt, args ...) do {printf("MPU: " fmt "\n", ## args); } while(0)
46 #endif
47 
48 /*
49  EXT_SYNC allows for frame synchronisation with an external device
50  such as a camera. When enabled the LSB of AccelZ holds the FSYNC bit
51  */
52 #ifndef INVENSENSE_EXT_SYNC_ENABLE
53 #define INVENSENSE_EXT_SYNC_ENABLE 0
54 #endif
55 
57 
58 #define MPU_SAMPLE_SIZE 14
59 #define MPU_FIFO_BUFFER_LEN 16
60 
61 #define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]))
62 #define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])
63 
64 /*
65  * RM-MPU-6000A-00.pdf, page 33, section 4.25 lists LSB sensitivity of
66  * gyro as 16.4 LSB/DPS at scale factor of +/- 2000dps (FS_SEL==3)
67  */
68 static const float GYRO_SCALE = (0.0174532f / 16.4f);
69 
70 /*
71  * RM-MPU-6000A-00.pdf, page 31, section 4.23 lists LSB sensitivity of
72  * accel as 4096 LSB/mg at scale factor of +/- 8g (AFS_SEL==2)
73  *
74  * See note below about accel scaling of engineering sample MPU6k
75  * variants however
76  */
77 
80  enum Rotation rotation)
82  , _temp_filter(1000, 1)
83  , _rotation(rotation)
84  , _dev(std::move(dev))
85 {
86 }
87 
89 {
90  if (_fifo_buffer != nullptr) {
92  }
93  delete _auxiliary_bus;
94 }
95 
98  enum Rotation rotation)
99 {
100  if (!dev) {
101  return nullptr;
102  }
104  new AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
105  if (!sensor || !sensor->_init()) {
106  delete sensor;
107  return nullptr;
108  }
109  if (sensor->_mpu_type == Invensense_MPU9250) {
110  sensor->_id = HAL_INS_MPU9250_I2C;
111  } else {
112  sensor->_id = HAL_INS_MPU60XX_I2C;
113  }
114 
115  return sensor;
116 }
117 
118 
121  enum Rotation rotation)
122 {
123  if (!dev) {
124  return nullptr;
125  }
127 
128  dev->set_read_flag(0x80);
129 
130  sensor = new AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
131  if (!sensor || !sensor->_init()) {
132  delete sensor;
133  return nullptr;
134  }
135  if (sensor->_mpu_type == Invensense_MPU9250) {
136  sensor->_id = HAL_INS_MPU9250_SPI;
137  } else if (sensor->_mpu_type == Invensense_MPU6500) {
138  sensor->_id = HAL_INS_MPU6500;
139  } else {
140  sensor->_id = HAL_INS_MPU60XX_SPI;
141  }
142 
143  return sensor;
144 }
145 
147 {
148 #ifdef INVENSENSE_DRDY_PIN
151 #endif
152 
153  bool success = _hardware_init();
154 
155  return success;
156 }
157 
159 {
160  uint8_t user_ctrl = _last_stat_user_ctrl;
162 
165  _register_write(MPUREG_USER_CTRL, user_ctrl);
173 
176 }
177 
179 {
181 }
182 
184 {
186  return;
187  }
188 
189  // initially run the bus at low speed
191 
192  // only used for wake-up in accelerometer only low power mode
194  hal.scheduler->delay(1);
195 
196  // always use FIFO
197  _fifo_reset();
198 
199  // grab the used instances
200  enum DevTypes gdev, adev;
201  switch (_mpu_type) {
202  case Invensense_MPU9250:
203  gdev = DEVTYPE_GYR_MPU9250;
204  adev = DEVTYPE_ACC_MPU9250;
205  break;
206  case Invensense_MPU6000:
207  case Invensense_MPU6500:
208  case Invensense_ICM20608:
209  case Invensense_ICM20602:
210  default:
211  gdev = DEVTYPE_GYR_MPU6000;
212  adev = DEVTYPE_ACC_MPU6000;
213  break;
214  case Invensense_ICM20789:
215  gdev = DEVTYPE_INS_ICM20789;
216  adev = DEVTYPE_INS_ICM20789;
217  break;
218  case Invensense_ICM20689:
219  gdev = DEVTYPE_INS_ICM20689;
220  adev = DEVTYPE_INS_ICM20689;
221  break;
222  }
223 
224  /*
225  setup temperature sensitivity and offset. This varies
226  considerably between parts
227  */
228  switch (_mpu_type) {
229  case Invensense_MPU9250:
230  temp_zero = 21;
231  temp_sensitivity = 1.0/340;
232  break;
233 
234  case Invensense_MPU6000:
235  case Invensense_MPU6500:
236  temp_zero = 36.53;
237  temp_sensitivity = 1.0/340;
238  break;
239 
240  case Invensense_ICM20608:
241  case Invensense_ICM20602:
242  temp_zero = 25;
243  temp_sensitivity = 1.0/326.8;
244  break;
245 
246  case Invensense_ICM20789:
247  temp_zero = 25;
248  temp_sensitivity = 0.003;
249  break;
250  case Invensense_ICM20689:
251  temp_zero = 25;
252  temp_sensitivity = 0.003;
253  break;
254  }
255 
258 
259  // setup ODR and on-sensor filtering
261 
262  // update backend sample rate
265 
266  // indicate what multiplier is appropriate for the sensors'
267  // readings to fit them into an int16_t:
269 
270  if (_fast_sampling) {
271  hal.console->printf("MPU[%u]: enabled fast sampling rate %uHz/%uHz\n",
273  }
274 
275  // set sample rate to 1000Hz and apply a software filter
276  // In this configuration, the gyro sample rate is 8kHz
278  hal.scheduler->delay(1);
279 
280  // Gyro scale 2000ยบ/s
282  hal.scheduler->delay(1);
283 
284  // read the product ID rev c has 1/2 the sensitivity of rev d
285  uint8_t product_id = _register_read(MPUREG_PRODUCT_ID);
286 
287  if (_mpu_type == Invensense_MPU6000 &&
288  ((product_id == MPU6000ES_REV_C4) ||
289  (product_id == MPU6000ES_REV_C5) ||
290  (product_id == MPU6000_REV_C4) ||
291  (product_id == MPU6000_REV_C5))) {
292  // Accel scale 8g (4096 LSB/g)
293  // Rev C has different scaling than rev D
295  _accel_scale = GRAVITY_MSS / 4096.f;
296  } else {
297  // Accel scale 16g (2048 LSB/g)
299  _accel_scale = GRAVITY_MSS / 2048.f;
300  }
301  hal.scheduler->delay(1);
302 
305  // this avoids a sensor bug, see description above
307  }
308 
309  // configure interrupt to fire when new data arrives
311  hal.scheduler->delay(1);
312 
313  // clear interrupt on any read, and hold the data ready pin high
314  // until we clear the interrupt. We don't do this for the 20789 as
315  // that sensor has already setup the appropriate config inside the
316  // baro driver.
317  if (_mpu_type != Invensense_ICM20789) {
319  v &= BIT_BYPASS_EN;
321  }
322 
323  // now that we have initialised, we set the bus speed to high
325 
326  _dev->get_semaphore()->give();
327 
328  // setup sensor rotations from probe()
331 
332  // setup scale factors for fifo data after downsampling
335 
336  // allocate fifo buffer
338  if (_fifo_buffer == nullptr) {
339  AP_HAL::panic("Invensense: Unable to allocate FIFO buffer");
340  }
341 
342  // start the timer process to read samples
344 }
345 
346 
347 /*
348  publish any pending data
349  */
351 {
354 
356 
357  return true;
358 }
359 
360 /*
361  accumulate new samples
362  */
364 {
365  // nothing to do
366 }
367 
369 {
370  if (_auxiliary_bus) {
371  return _auxiliary_bus;
372  }
373 
374  if (_has_auxiliary_bus()) {
376  }
377 
378  return _auxiliary_bus;
379 }
380 
381 /*
382  * Return true if the Invensense has new data available for reading.
383  *
384  * We use the data ready pin if it is available. Otherwise, read the
385  * status register.
386  */
388 {
389  if (_drdy_pin) {
390  return _drdy_pin->read() != 0;
391  }
392  uint8_t status = _register_read(MPUREG_INT_STATUS);
393  return (status & BIT_RAW_RDY_INT) != 0;
394 }
395 
396 /*
397  * Timer process to poll for new data from the Invensense. Called from bus thread with semaphore held
398  */
400 {
401  _read_fifo();
402 }
403 
404 bool AP_InertialSensor_Invensense::_accumulate(uint8_t *samples, uint8_t n_samples)
405 {
406  for (uint8_t i = 0; i < n_samples; i++) {
407  const uint8_t *data = samples + MPU_SAMPLE_SIZE * i;
409  bool fsync_set = false;
410 
411 #if INVENSENSE_EXT_SYNC_ENABLE
412  fsync_set = (int16_val(data, 2) & 1U) != 0;
413 #endif
414 
415  accel = Vector3f(int16_val(data, 1),
416  int16_val(data, 0),
417  -int16_val(data, 2));
418  accel *= _accel_scale;
419 
420  int16_t t2 = int16_val(data, 3);
421  if (!_check_raw_temp(t2)) {
422  debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
423  _fifo_reset();
424  return false;
425  }
426  float temp = t2 * temp_sensitivity + temp_zero;
427 
428  gyro = Vector3f(int16_val(data, 5),
429  int16_val(data, 4),
430  -int16_val(data, 6));
431  gyro *= GYRO_SCALE;
432 
435 
436  _notify_new_accel_raw_sample(_accel_instance, accel, 0, fsync_set);
438 
440  }
441  return true;
442 }
443 
444 /*
445  when doing fast sampling the sensor gives us 8k samples/second. Every 2nd accel sample is a duplicate.
446 
447  To filter this we first apply a 1p low pass filter at 188Hz, then we
448  average over 8 samples to bring the data rate down to 1kHz. This
449  gives very good aliasing rejection at frequencies well above what
450  can be handled with 1kHz sample rates.
451  */
452 bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
453 {
454  int32_t tsum = 0;
455  const int32_t clip_limit = AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS / _accel_scale;
456  bool clipped = false;
457  bool ret = true;
458 
459  for (uint8_t i = 0; i < n_samples; i++) {
460  const uint8_t *data = samples + MPU_SAMPLE_SIZE * i;
461 
462  // use temperatue to detect FIFO corruption
463  int16_t t2 = int16_val(data, 3);
464  if (!_check_raw_temp(t2)) {
465  debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
466  _fifo_reset();
467  ret = false;
468  break;
469  }
470  tsum += t2;
471 
472  if ((_accum.count & 1) == 0) {
473  // accel data is at 4kHz
474  Vector3f a(int16_val(data, 1),
475  int16_val(data, 0),
476  -int16_val(data, 2));
477  if (fabsf(a.x) > clip_limit ||
478  fabsf(a.y) > clip_limit ||
479  fabsf(a.z) > clip_limit) {
480  clipped = true;
481  }
482  _accum.accel += _accum.accel_filter.apply(a);
483  Vector3f a2 = a * _accel_scale;
485  }
486 
487  Vector3f g(int16_val(data, 5),
488  int16_val(data, 4),
489  -int16_val(data, 6));
490 
491  Vector3f g2 = g * GYRO_SCALE;
493 
494  _accum.gyro += _accum.gyro_filter.apply(g);
495  _accum.count++;
496 
497  if (_accum.count == _fifo_downsample_rate) {
498 
499  _accum.accel *= _fifo_accel_scale;
500  _accum.gyro *= _fifo_gyro_scale;
501 
504 
507 
508  _accum.accel.zero();
509  _accum.gyro.zero();
510  _accum.count = 0;
511  }
512  }
513 
514  if (clipped) {
516  }
517 
518  if (ret) {
519  float temp = (static_cast<float>(tsum)/n_samples)*temp_sensitivity + temp_zero;
521  }
522 
523  return ret;
524 }
525 
527 {
528  uint8_t n_samples;
529  uint16_t bytes_read;
530  uint8_t *rx = _fifo_buffer;
531  bool need_reset = false;
532 
533  if (!_block_read(MPUREG_FIFO_COUNTH, rx, 2)) {
534  goto check_registers;
535  }
536 
537  bytes_read = uint16_val(rx, 0);
538  n_samples = bytes_read / MPU_SAMPLE_SIZE;
539 
540  if (n_samples == 0) {
541  /* Not enough data in FIFO */
542  goto check_registers;
543  }
544 
545  /*
546  testing has shown that if we have more than 32 samples in the
547  FIFO then some of those samples will be corrupt. It always is
548  the ones at the end of the FIFO, so clear those with a reset
549  once we've read the first 24. Reading 24 gives us the normal
550  number of samples for fast sampling at 400Hz
551 
552  On I2C with the much lower clock rates we need a lower threshold
553  or we may never catch up
554  */
556  if (n_samples > 4) {
557  need_reset = true;
558  n_samples = 4;
559  }
560  } else {
561  if (n_samples > 32) {
562  need_reset = true;
563  n_samples = 24;
564  }
565  }
566 
567  while (n_samples > 0) {
568  uint8_t n = MIN(n_samples, MPU_FIFO_BUFFER_LEN);
569  if (!_dev->set_chip_select(true)) {
571  goto check_registers;
572  }
573  } else {
574  // this ensures we keep things nicely setup for DMA
575  uint8_t reg = MPUREG_FIFO_R_W | 0x80;
576  if (!_dev->transfer(&reg, 1, nullptr, 0)) {
577  _dev->set_chip_select(false);
578  goto check_registers;
579  }
580  memset(rx, 0, n * MPU_SAMPLE_SIZE);
581  if (!_dev->transfer(rx, n * MPU_SAMPLE_SIZE, rx, n * MPU_SAMPLE_SIZE)) {
582  hal.console->printf("MPU60x0: error in fifo read %u bytes\n", n * MPU_SAMPLE_SIZE);
583  _dev->set_chip_select(false);
584  goto check_registers;
585  }
586  _dev->set_chip_select(false);
587  }
588 
589  if (_fast_sampling) {
590  if (!_accumulate_sensor_rate_sampling(rx, n)) {
591  debug("IMU[%u] stop at %u of %u", _accel_instance, n_samples, bytes_read/MPU_SAMPLE_SIZE);
592  break;
593  }
594  } else {
595  if (!_accumulate(rx, n)) {
596  break;
597  }
598  }
599  n_samples -= n;
600  }
601 
602  if (need_reset) {
603  //debug("fifo reset n_samples %u", bytes_read/MPU_SAMPLE_SIZE);
604  _fifo_reset();
605  }
606 
607 check_registers:
608  // check next register value for correctness
610  if (!_dev->check_next_register()) {
613  }
615 }
616 
617 /*
618  fetch temperature in order to detect FIFO sync errors
619 */
621 {
622  if (abs(t2 - _raw_temp) < 400) {
623  // cached copy OK
624  return true;
625  }
626  uint8_t trx[2];
627  if (_block_read(MPUREG_TEMP_OUT_H, trx, 2)) {
628  _raw_temp = int16_val(trx, 0);
629  }
630  return (abs(t2 - _raw_temp) < 400);
631 }
632 
633 bool AP_InertialSensor_Invensense::_block_read(uint8_t reg, uint8_t *buf,
634  uint32_t size)
635 {
636  return _dev->read_registers(reg, buf, size);
637 }
638 
640 {
641  uint8_t val = 0;
642  _dev->read_registers(reg, &val, 1);
643  return val;
644 }
645 
646 void AP_InertialSensor_Invensense::_register_write(uint8_t reg, uint8_t val, bool checked)
647 {
648  _dev->write_register(reg, val, checked);
649 }
650 
651 /*
652  set the DLPF filter frequency. Assumes caller has taken semaphore
653  */
655 {
656  uint8_t config;
657 
658 #if INVENSENSE_EXT_SYNC_ENABLE
659  // add in EXT_SYNC bit if enabled
661 #else
662  config = 0;
663 #endif
664 
665  // assume 1kHz sampling to start
667  _backend_rate_hz = 1000;
668 
671  if (_fast_sampling) {
672  if (get_sample_rate_hz() <= 1000) {
674  } else if (get_sample_rate_hz() <= 2000) {
676  } else {
678  }
679  // calculate rate we will be giving samples to the backend
681 
682  // for logging purposes set the oversamping rate
685 
688 
689  /* set divider for internal sample rate to 0x1F when fast
690  sampling enabled. This reduces the impact of the slave
691  sensor on the sample rate. It ends up with around 75Hz
692  slave rate, and reduces the impact on the gyro and accel
693  sample rate, ending up with around 7760Hz gyro rate and
694  3880Hz accel rate
695  */
697  }
698  }
699 
700  if (_fast_sampling) {
701  // this gives us 8kHz sampling on gyros and 4kHz on accels
702  config |= BITS_DLPF_CFG_256HZ_NOLPF2;
703  } else {
704  // limit to 1kHz if not on SPI
705  config |= BITS_DLPF_CFG_188HZ;
706  }
707 
709  _register_write(MPUREG_CONFIG, config, true);
710 
711  if (_mpu_type != Invensense_MPU6000) {
712  if (_fast_sampling) {
713  // setup for 4kHz accels
715  } else {
716  uint8_t fifo_size = (_mpu_type == Invensense_ICM20789 || _mpu_type == Invensense_ICM20689) ? 1:0;
718  }
719  }
720 }
721 
722 /*
723  check whoami for sensor type
724  */
726 {
727  uint8_t whoami = _register_read(MPUREG_WHOAMI);
728  switch (whoami) {
729  case MPU_WHOAMI_6000:
731  return true;
732  case MPU_WHOAMI_6500:
734  return true;
735  case MPU_WHOAMI_MPU9250:
736  case MPU_WHOAMI_MPU9255:
738  return true;
739  case MPU_WHOAMI_20608:
741  return true;
742  case MPU_WHOAMI_20602:
744  return true;
745  case MPU_WHOAMI_ICM20789:
748  return true;
749  case MPU_WHOAMI_ICM20689:
751  return true;
752  }
753  // not a value WHOAMI result
754  return false;
755 }
756 
757 
759 {
761  return false;
762  }
763 
764  // setup for register checking. We check much less often on I2C
765  // where the cost of the checks is higher
767 
768  // initially run the bus at low speed
770 
771  if (!_check_whoami()) {
772  _dev->get_semaphore()->give();
773  return false;
774  }
775 
776  // Chip reset
777  uint8_t tries;
778  for (tries = 0; tries < 5; tries++) {
780 
781  /* First disable the master I2C to avoid hanging the slaves on the
782  * aulixiliar I2C bus - it will be enabled again if the AuxiliaryBus
783  * is used */
785  _last_stat_user_ctrl &= ~BIT_USER_CTRL_I2C_MST_EN;
787  hal.scheduler->delay(10);
788  }
789 
790  /* reset device */
792  hal.scheduler->delay(100);
793 
794  /* bus-dependent initialization */
796  /* Disable I2C bus if SPI selected (Recommended in Datasheet to be
797  * done just after the device is reset) */
800  }
801 
802  /* bus-dependent initialization */
804  /* Enable I2C bypass to access internal device */
806  }
807 
808 
809  // Wake up device and select GyroZ clock. Note that the
810  // Invensense starts up in sleep mode, and it can take some time
811  // for it to come out of sleep
813  hal.scheduler->delay(5);
814 
815  // check it has woken up
817  break;
818  }
819 
820  hal.scheduler->delay(10);
821  if (_data_ready()) {
822  break;
823  }
824  }
825 
827 
828  if (tries == 5) {
829  hal.console->printf("Failed to boot Invensense 5 times\n");
830  _dev->get_semaphore()->give();
831  return false;
832  }
833 
836  // this avoids a sensor bug, see description above
838  }
839  _dev->get_semaphore()->give();
840 
841  return true;
842 }
843 
845  uint8_t instance)
846  : AuxiliaryBusSlave(bus, addr, instance)
847  , _mpu_addr(MPUREG_I2C_SLV0_ADDR + _instance * 3)
848  , _mpu_reg(_mpu_addr + 1)
849  , _mpu_ctrl(_mpu_addr + 2)
850  , _mpu_do(MPUREG_I2C_SLV0_DO + _instance)
851 {
852 }
853 
855  uint8_t *out)
856 {
858  uint8_t addr;
859 
860  /* Ensure the slave read/write is disabled before changing the registers */
861  backend._register_write(_mpu_ctrl, 0);
862 
863  if (out) {
864  backend._register_write(_mpu_do, *out);
865  addr = _addr;
866  } else {
867  addr = _addr | BIT_READ_FLAG;
868  }
869 
870  backend._register_write(_mpu_addr, addr);
871  backend._register_write(_mpu_reg, reg);
872  backend._register_write(_mpu_ctrl, BIT_I2C_SLVX_EN | size);
873 
874  return 0;
875 }
876 
878  uint8_t size)
879 {
880  assert(buf);
881 
882  if (_registered) {
883  hal.console->printf("Error: can't passthrough when slave is already configured\n");
884  return -1;
885  }
886 
887  int r = _set_passthrough(reg, size);
888  if (r < 0) {
889  return r;
890  }
891 
892  /* wait the value to be read from the slave and read it back */
893  hal.scheduler->delay(10);
894 
896  if (!backend._block_read(MPUREG_EXT_SENS_DATA_00 + _ext_sens_data, buf, size)) {
897  return -1;
898  }
899 
900  /* disable new reads */
901  backend._register_write(_mpu_ctrl, 0);
902 
903  return size;
904 }
905 
907 {
908  if (_registered) {
909  hal.console->printf("Error: can't passthrough when slave is already configured\n");
910  return -1;
911  }
912 
913  int r = _set_passthrough(reg, 1, &val);
914  if (r < 0) {
915  return r;
916  }
917 
918  /* wait the value to be written to the slave */
919  hal.scheduler->delay(10);
920 
922 
923  /* disable new writes */
924  backend._register_write(_mpu_ctrl, 0);
925 
926  return 1;
927 }
928 
930 {
931  if (!_registered) {
932  hal.console->printf("Error: can't read before configuring slave\n");
933  return -1;
934  }
935 
937  if (!backend._block_read(MPUREG_EXT_SENS_DATA_00 + _ext_sens_data, buf, _sample_size)) {
938  return -1;
939  }
940 
941  return _sample_size;
942 }
943 
944 /* Invensense provides up to 5 slave devices, but the 5th is way too different to
945  * configure and is seldom used */
947  : AuxiliaryBus(backend, 4, devid)
948 {
949 }
950 
952 {
953  return static_cast<AP_InertialSensor_Invensense&>(_ins_backend)._dev->get_semaphore();
954 }
955 
957 {
958  /* Enable slaves on Invensense if this is the first time */
959  if (_ext_sens_data == 0) {
961  }
962 
963  return new AP_Invensense_AuxiliaryBusSlave(*this, addr, instance);
964 }
965 
967 {
969 
970  if (backend._mpu_type == AP_InertialSensor_Invensense::Invensense_ICM20789) {
971  // on 20789 we can't enable slaves if we want to be able to use the baro
972  return;
973  }
974 
975  if (!backend._dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
976  return;
977  }
978 
979  /* Enable the I2C master to slaves on the auxiliary I2C bus*/
980  if (!(backend._last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN)) {
981  backend._last_stat_user_ctrl |= BIT_USER_CTRL_I2C_MST_EN;
982  backend._register_write(MPUREG_USER_CTRL, backend._last_stat_user_ctrl);
983  }
984 
985  /* stop condition between reads; clock at 400kHz */
986  backend._register_write(MPUREG_I2C_MST_CTRL,
988 
989  /* Hard-code divider for internal sample rate, 1 kHz, resulting in a
990  * sample rate of 100Hz */
991  backend._register_write(MPUREG_I2C_SLV4_CTRL, 9);
992 
993  /* All slaves are subject to the sample rate */
994  backend._register_write(MPUREG_I2C_MST_DELAY_CTRL,
997 
998  backend._dev->get_semaphore()->give();
999 }
1000 
1002  uint8_t reg, uint8_t size)
1003 {
1004  if (_ext_sens_data + size > MAX_EXT_SENS_DATA) {
1005  return -1;
1006  }
1007 
1008  AP_Invensense_AuxiliaryBusSlave *mpu_slave =
1009  static_cast<AP_Invensense_AuxiliaryBusSlave*>(slave);
1010  mpu_slave->_set_passthrough(reg, size);
1011  mpu_slave->_ext_sens_data = _ext_sens_data;
1012  _ext_sens_data += size;
1013 
1014  return 0;
1015 }
1016 
1018 {
1020  return backend._dev->register_periodic_callback(period_usec, cb);
1021 }
t2
Definition: calcH_MAG.c:1
#define BIT_LATCH_INT_EN
Definition: ICM20789.cpp:26
#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)
void _set_gyro_raw_sample_rate(uint8_t instance, uint16_t rate_hz)
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
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define HAL_INS_MPU9250_I2C
Definition: AP_HAL_Boards.h:88
int passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) override
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
void _inc_accel_error_count(uint8_t instance)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint32_t get_bus_id(void) const
Definition: Device.h:60
#define MPU_FIFO_BUFFER_LEN
T apply(const T &sample)
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
virtual AP_HAL::Semaphore * get_semaphore()=0
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
#define BIT_USER_CTRL_I2C_MST_EN
Definition: ICM20789.cpp:28
AP_HAL::Semaphore * get_semaphore() override
bool _accumulate(uint8_t *samples, uint8_t n_samples)
AP_HAL::Util * util
Definition: HAL.h:115
AuxiliaryBus & _bus
Definition: AuxiliaryBus.h:85
void notify_accel_fifo_reset(uint8_t instance)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
#define debug(fmt, args ...)
AP_Invensense_AuxiliaryBus * _auxiliary_bus
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool enable_fast_sampling(uint8_t instance)
#define MPUREG_WHOAMI
Definition: ICM20789.cpp:19
Rotation
Definition: rotations.h:27
#define HAL_INS_MPU6500
Definition: AP_HAL_Boards.h:92
uint32_t get_bus_id_devtype(uint8_t devtype)
Definition: Device.h:255
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
#define BIT_USER_CTRL_I2C_IF_DIS
Definition: ICM20789.cpp:30
#define MIN(a, b)
Definition: usb_conf.h:215
AP_HAL::OwnPtr< AP_HAL::Device > _dev
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
Definition: Device.cpp:39
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
#define MPUREG_CONFIG_EXT_SYNC_SHIFT
virtual void mode(uint8_t output)=0
bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
virtual void delay(uint16_t ms)=0
uint8_t _sample_size
Definition: AuxiliaryBus.h:90
#define BIT_PWR_MGMT_1_CLK_ZGYRO
Definition: ICM20789.cpp:32
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
AP_InertialSensor_Invensense(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define uint16_val(v, idx)
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) override
#define GRAVITY_MSS
Definition: definitions.h:47
virtual bool set_speed(Speed speed)=0
int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg, uint8_t size) override
#define MPU_WHOAMI_MPU9250
void increment_clip_count(uint8_t instance)
T y
Definition: vector3.h:67
void * PeriodicHandle
Definition: Device.h:42
enum BusType bus_type(void) const
Definition: Device.h:50
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
void _set_gyro_sensor_rate_sampling_enabled(uint8_t instance, bool value)
static AP_InertialSensor_Invensense & from(AP_InertialSensor_Backend &backend)
T z
Definition: vector3.h:67
void _notify_new_accel_sensor_rate_sample(uint8_t instance, const Vector3f &accel)
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)
int passthrough_write(uint8_t reg, uint8_t val) override
virtual bool set_chip_select(bool set)
Definition: Device.h:214
virtual bool give()=0
AverageFilterUInt16_Size4 _temp_filter
Definition: Filter.cpp:23
float v
Definition: Printf.cpp:15
AP_InertialSensor_Backend & get_backend()
Definition: AuxiliaryBus.h:100
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
#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)
void notify_gyro_fifo_reset(uint8_t instance)
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
AP_InertialSensor_Backend & _ins_backend
Definition: AuxiliaryBus.h:146
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
void _publish_temperature(uint8_t instance, float temperature)
void _set_accel_sensor_rate_sampling_enabled(uint8_t instance, bool value)
#define HAL_INS_MPU60XX_I2C
Definition: AP_HAL_Boards.h:80
virtual uint8_t read()=0
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
bool check_next_register(void)
Definition: Device.cpp:85
void _set_accel_oversampling(uint8_t instance, uint8_t n)
void _set_accel_raw_sample_rate(uint8_t instance, uint16_t rate_hz)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define INVENSENSE_DRDY_PIN
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
struct AP_InertialSensor_Invensense::@122 _accum
void _set_raw_sample_accel_multiplier(uint8_t instance, uint16_t mul)
void _inc_gyro_error_count(uint8_t instance)
static const float GYRO_SCALE
void _register_write(uint8_t reg, uint8_t val, bool checked=false)
void _notify_new_gyro_sensor_rate_sample(uint8_t instance, const Vector3f &gyro)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
int _set_passthrough(uint8_t reg, uint8_t size, uint8_t *out=nullptr)
#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
AP_Invensense_AuxiliaryBus(AP_InertialSensor_Invensense &backend, uint32_t devid)
AuxiliaryBusSlave * _instantiate_slave(uint8_t addr, uint8_t instance) override
T x
Definition: vector3.h:67
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define MPUREG_USER_CTRL
Definition: ICM20789.cpp:20
AP_Invensense_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance)