AP_InertialSensor_Invensense.cpp 32 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. driver for all supported Invensense IMUs, including MPU6000, MPU9250
  15. ICM-20608 and ICM-20602
  16. */
  17. #include <assert.h>
  18. #include <utility>
  19. #include <stdio.h>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include "AP_InertialSensor_Invensense.h"
  22. extern const AP_HAL::HAL& hal;
  23. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  24. #include <AP_HAL_Linux/GPIO.h>
  25. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
  26. #define INVENSENSE_DRDY_PIN BBB_P8_14
  27. #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  28. #define INVENSENSE_EXT_SYNC_ENABLE 1
  29. #endif
  30. #endif
  31. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  32. // hal.console can be accessed from bus threads on ChibiOS
  33. #define debug(fmt, args ...) do {hal.console->printf("MPU: " fmt "\n", ## args); } while(0)
  34. #else
  35. #define debug(fmt, args ...) do {printf("MPU: " fmt "\n", ## args); } while(0)
  36. #endif
  37. /*
  38. EXT_SYNC allows for frame synchronisation with an external device
  39. such as a camera. When enabled the LSB of AccelZ holds the FSYNC bit
  40. */
  41. #ifndef INVENSENSE_EXT_SYNC_ENABLE
  42. #define INVENSENSE_EXT_SYNC_ENABLE 0
  43. #endif
  44. #include "AP_InertialSensor_Invensense_registers.h"
  45. #define MPU_SAMPLE_SIZE 14
  46. #define MPU_FIFO_BUFFER_LEN 16
  47. #define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]))
  48. #define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])
  49. /*
  50. * RM-MPU-6000A-00.pdf, page 31, section 4.23 lists LSB sensitivity of
  51. * accel as 4096 LSB/mg at scale factor of +/- 8g (AFS_SEL==2)
  52. *
  53. * See note below about accel scaling of engineering sample MPU6k
  54. * variants however
  55. */
  56. AP_InertialSensor_Invensense::AP_InertialSensor_Invensense(AP_InertialSensor &imu,
  57. AP_HAL::OwnPtr<AP_HAL::Device> dev,
  58. enum Rotation rotation)
  59. : AP_InertialSensor_Backend(imu)
  60. , _temp_filter(1000, 1)
  61. , _rotation(rotation)
  62. , _dev(std::move(dev))
  63. {
  64. }
  65. AP_InertialSensor_Invensense::~AP_InertialSensor_Invensense()
  66. {
  67. if (_fifo_buffer != nullptr) {
  68. hal.util->free_type(_fifo_buffer, MPU_FIFO_BUFFER_LEN * MPU_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE);
  69. }
  70. delete _auxiliary_bus;
  71. }
  72. AP_InertialSensor_Backend *AP_InertialSensor_Invensense::probe(AP_InertialSensor &imu,
  73. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  74. enum Rotation rotation)
  75. {
  76. if (!dev) {
  77. return nullptr;
  78. }
  79. AP_InertialSensor_Invensense *sensor =
  80. new AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
  81. if (!sensor || !sensor->_init()) {
  82. delete sensor;
  83. return nullptr;
  84. }
  85. if (sensor->_mpu_type == Invensense_MPU9250) {
  86. sensor->_id = HAL_INS_MPU9250_I2C;
  87. } else {
  88. sensor->_id = HAL_INS_MPU60XX_I2C;
  89. }
  90. return sensor;
  91. }
  92. AP_InertialSensor_Backend *AP_InertialSensor_Invensense::probe(AP_InertialSensor &imu,
  93. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev,
  94. enum Rotation rotation)
  95. {
  96. if (!dev) {
  97. return nullptr;
  98. }
  99. AP_InertialSensor_Invensense *sensor;
  100. dev->set_read_flag(0x80);
  101. sensor = new AP_InertialSensor_Invensense(imu, std::move(dev), rotation);
  102. if (!sensor || !sensor->_init()) {
  103. delete sensor;
  104. return nullptr;
  105. }
  106. if (sensor->_mpu_type == Invensense_MPU9250) {
  107. sensor->_id = HAL_INS_MPU9250_SPI;
  108. } else if (sensor->_mpu_type == Invensense_MPU6500) {
  109. sensor->_id = HAL_INS_MPU6500;
  110. } else {
  111. sensor->_id = HAL_INS_MPU60XX_SPI;
  112. }
  113. return sensor;
  114. }
  115. bool AP_InertialSensor_Invensense::_init()
  116. {
  117. #ifdef INVENSENSE_DRDY_PIN
  118. _drdy_pin = hal.gpio->channel(INVENSENSE_DRDY_PIN);
  119. _drdy_pin->mode(HAL_GPIO_INPUT);
  120. #endif
  121. bool success = _hardware_init();
  122. return success;
  123. }
  124. void AP_InertialSensor_Invensense::_fifo_reset()
  125. {
  126. uint8_t user_ctrl = _last_stat_user_ctrl;
  127. user_ctrl &= ~(BIT_USER_CTRL_FIFO_RESET | BIT_USER_CTRL_FIFO_EN);
  128. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  129. _register_write(MPUREG_FIFO_EN, 0);
  130. _register_write(MPUREG_USER_CTRL, user_ctrl);
  131. _register_write(MPUREG_USER_CTRL, user_ctrl | BIT_USER_CTRL_FIFO_RESET);
  132. _register_write(MPUREG_USER_CTRL, user_ctrl | BIT_USER_CTRL_FIFO_EN);
  133. _register_write(MPUREG_FIFO_EN, BIT_XG_FIFO_EN | BIT_YG_FIFO_EN |
  134. BIT_ZG_FIFO_EN | BIT_ACCEL_FIFO_EN | BIT_TEMP_FIFO_EN, true);
  135. hal.scheduler->delay_microseconds(1);
  136. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  137. _last_stat_user_ctrl = user_ctrl | BIT_USER_CTRL_FIFO_EN;
  138. notify_accel_fifo_reset(_accel_instance);
  139. notify_gyro_fifo_reset(_gyro_instance);
  140. }
  141. bool AP_InertialSensor_Invensense::_has_auxiliary_bus()
  142. {
  143. return _dev->bus_type() != AP_HAL::Device::BUS_TYPE_I2C;
  144. }
  145. void AP_InertialSensor_Invensense::start()
  146. {
  147. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  148. return;
  149. }
  150. // initially run the bus at low speed
  151. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  152. // only used for wake-up in accelerometer only low power mode
  153. _register_write(MPUREG_PWR_MGMT_2, 0x00);
  154. hal.scheduler->delay(1);
  155. // always use FIFO
  156. _fifo_reset();
  157. // grab the used instances
  158. enum DevTypes gdev, adev;
  159. switch (_mpu_type) {
  160. case Invensense_MPU9250:
  161. gdev = DEVTYPE_GYR_MPU9250;
  162. adev = DEVTYPE_ACC_MPU9250;
  163. break;
  164. case Invensense_ICM20602:
  165. gdev = DEVTYPE_INS_ICM20602;
  166. adev = DEVTYPE_INS_ICM20602;
  167. break;
  168. case Invensense_ICM20601:
  169. gdev = DEVTYPE_INS_ICM20601;
  170. adev = DEVTYPE_INS_ICM20601;
  171. break;
  172. case Invensense_MPU6000:
  173. case Invensense_MPU6500:
  174. case Invensense_ICM20608:
  175. default:
  176. gdev = DEVTYPE_GYR_MPU6000;
  177. adev = DEVTYPE_ACC_MPU6000;
  178. break;
  179. case Invensense_ICM20789:
  180. gdev = DEVTYPE_INS_ICM20789;
  181. adev = DEVTYPE_INS_ICM20789;
  182. break;
  183. case Invensense_ICM20689:
  184. gdev = DEVTYPE_INS_ICM20689;
  185. adev = DEVTYPE_INS_ICM20689;
  186. break;
  187. }
  188. /*
  189. setup temperature sensitivity and offset. This varies
  190. considerably between parts
  191. */
  192. switch (_mpu_type) {
  193. case Invensense_MPU9250:
  194. temp_zero = 21.0f;
  195. temp_sensitivity = 1.0f/340;
  196. break;
  197. case Invensense_MPU6000:
  198. case Invensense_MPU6500:
  199. temp_zero = 36.53f;
  200. temp_sensitivity = 1.0f/340;
  201. break;
  202. case Invensense_ICM20608:
  203. case Invensense_ICM20602:
  204. case Invensense_ICM20601:
  205. temp_zero = 25.0f;
  206. temp_sensitivity = 1.0f/326.8f;
  207. break;
  208. case Invensense_ICM20789:
  209. temp_zero = 25.0f;
  210. temp_sensitivity = 0.003f;
  211. break;
  212. case Invensense_ICM20689:
  213. temp_zero = 25.0f;
  214. temp_sensitivity = 0.003f;
  215. break;
  216. }
  217. _gyro_instance = _imu.register_gyro(1000, _dev->get_bus_id_devtype(gdev));
  218. _accel_instance = _imu.register_accel(1000, _dev->get_bus_id_devtype(adev));
  219. // setup ODR and on-sensor filtering
  220. _set_filter_register();
  221. // update backend sample rate
  222. _set_accel_raw_sample_rate(_accel_instance, _backend_rate_hz);
  223. _set_gyro_raw_sample_rate(_gyro_instance, _backend_rate_hz);
  224. // indicate what multiplier is appropriate for the sensors'
  225. // readings to fit them into an int16_t:
  226. _set_raw_sample_accel_multiplier(_accel_instance, multiplier_accel);
  227. if (_fast_sampling) {
  228. hal.console->printf("MPU[%u]: enabled fast sampling rate %uHz/%uHz\n",
  229. _accel_instance, _backend_rate_hz*_fifo_downsample_rate, _backend_rate_hz);
  230. }
  231. // set sample rate to 1000Hz and apply a software filter
  232. // In this configuration, the gyro sample rate is 8kHz
  233. _register_write(MPUREG_SMPLRT_DIV, 0, true);
  234. hal.scheduler->delay(1);
  235. // Gyro scale 2000º/s
  236. _register_write(MPUREG_GYRO_CONFIG, BITS_GYRO_FS_2000DPS, true);
  237. hal.scheduler->delay(1);
  238. // read the product ID rev c has 1/2 the sensitivity of rev d
  239. uint8_t product_id = _register_read(MPUREG_PRODUCT_ID);
  240. if (_mpu_type == Invensense_MPU6000 &&
  241. ((product_id == MPU6000ES_REV_C4) ||
  242. (product_id == MPU6000ES_REV_C5) ||
  243. (product_id == MPU6000_REV_C4) ||
  244. (product_id == MPU6000_REV_C5))) {
  245. // Accel scale 8g (4096 LSB/g)
  246. // Rev C has different scaling than rev D
  247. _register_write(MPUREG_ACCEL_CONFIG,1<<3, true);
  248. _accel_scale = GRAVITY_MSS / 4096.f;
  249. _gyro_scale = (radians(1) / 16.4f);
  250. } else if (_mpu_type == Invensense_ICM20601) {
  251. // Accel scale 32g (4096 LSB/g)
  252. _register_write(MPUREG_ACCEL_CONFIG,1<<3, true);
  253. _accel_scale = GRAVITY_MSS / 4096.f;
  254. _gyro_scale = (radians(1) / 8.2f);
  255. _clip_limit = 29.5f * GRAVITY_MSS;
  256. } else {
  257. // Accel scale 16g (2048 LSB/g)
  258. _register_write(MPUREG_ACCEL_CONFIG,3<<3, true);
  259. _accel_scale = GRAVITY_MSS / 2048.f;
  260. _gyro_scale = (radians(1) / 16.4f);
  261. }
  262. hal.scheduler->delay(1);
  263. if (_mpu_type == Invensense_ICM20608 ||
  264. _mpu_type == Invensense_ICM20602 ||
  265. _mpu_type == Invensense_ICM20601) {
  266. // this avoids a sensor bug, see description above
  267. _register_write(MPUREG_ICM_UNDOC1, MPUREG_ICM_UNDOC1_VALUE, true);
  268. }
  269. // configure interrupt to fire when new data arrives
  270. _register_write(MPUREG_INT_ENABLE, BIT_RAW_RDY_EN);
  271. hal.scheduler->delay(1);
  272. // clear interrupt on any read, and hold the data ready pin high
  273. // until we clear the interrupt. We don't do this for the 20789 as
  274. // that sensor has already setup the appropriate config inside the
  275. // baro driver.
  276. if (_mpu_type != Invensense_ICM20789) {
  277. uint8_t v = _register_read(MPUREG_INT_PIN_CFG) | BIT_INT_RD_CLEAR | BIT_LATCH_INT_EN;
  278. v &= BIT_BYPASS_EN;
  279. _register_write(MPUREG_INT_PIN_CFG, v);
  280. }
  281. // now that we have initialised, we set the bus speed to high
  282. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  283. _dev->get_semaphore()->give();
  284. // setup sensor rotations from probe()
  285. set_gyro_orientation(_gyro_instance, _rotation);
  286. set_accel_orientation(_accel_instance, _rotation);
  287. // setup scale factors for fifo data after downsampling
  288. _fifo_accel_scale = _accel_scale / (MAX(_fifo_downsample_rate,2)/2);
  289. _fifo_gyro_scale = _gyro_scale / _fifo_downsample_rate;
  290. // allocate fifo buffer
  291. _fifo_buffer = (uint8_t *)hal.util->malloc_type(MPU_FIFO_BUFFER_LEN * MPU_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE);
  292. if (_fifo_buffer == nullptr) {
  293. AP_HAL::panic("Invensense: Unable to allocate FIFO buffer");
  294. }
  295. // start the timer process to read samples
  296. _dev->register_periodic_callback(1000000UL / _backend_rate_hz, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Invensense::_poll_data, void));
  297. }
  298. /*
  299. publish any pending data
  300. */
  301. bool AP_InertialSensor_Invensense::update()
  302. {
  303. update_accel(_accel_instance);
  304. update_gyro(_gyro_instance);
  305. _publish_temperature(_accel_instance, _temp_filtered);
  306. return true;
  307. }
  308. /*
  309. accumulate new samples
  310. */
  311. void AP_InertialSensor_Invensense::accumulate()
  312. {
  313. // nothing to do
  314. }
  315. AuxiliaryBus *AP_InertialSensor_Invensense::get_auxiliary_bus()
  316. {
  317. if (_auxiliary_bus) {
  318. return _auxiliary_bus;
  319. }
  320. if (_has_auxiliary_bus()) {
  321. _auxiliary_bus = new AP_Invensense_AuxiliaryBus(*this, _dev->get_bus_id());
  322. }
  323. return _auxiliary_bus;
  324. }
  325. /*
  326. * Return true if the Invensense has new data available for reading.
  327. *
  328. * We use the data ready pin if it is available. Otherwise, read the
  329. * status register.
  330. */
  331. bool AP_InertialSensor_Invensense::_data_ready()
  332. {
  333. if (_drdy_pin) {
  334. return _drdy_pin->read() != 0;
  335. }
  336. uint8_t status = _register_read(MPUREG_INT_STATUS);
  337. return (status & BIT_RAW_RDY_INT) != 0;
  338. }
  339. /*
  340. * Timer process to poll for new data from the Invensense. Called from bus thread with semaphore held
  341. */
  342. void AP_InertialSensor_Invensense::_poll_data()
  343. {
  344. _read_fifo();
  345. }
  346. bool AP_InertialSensor_Invensense::_accumulate(uint8_t *samples, uint8_t n_samples)
  347. {
  348. for (uint8_t i = 0; i < n_samples; i++) {
  349. const uint8_t *data = samples + MPU_SAMPLE_SIZE * i;
  350. Vector3f accel, gyro;
  351. bool fsync_set = false;
  352. #if INVENSENSE_EXT_SYNC_ENABLE
  353. fsync_set = (int16_val(data, 2) & 1U) != 0;
  354. #endif
  355. accel = Vector3f(int16_val(data, 1),
  356. int16_val(data, 0),
  357. -int16_val(data, 2));
  358. accel *= _accel_scale;
  359. int16_t t2 = int16_val(data, 3);
  360. if (!_check_raw_temp(t2)) {
  361. debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
  362. _fifo_reset();
  363. return false;
  364. }
  365. float temp = t2 * temp_sensitivity + temp_zero;
  366. gyro = Vector3f(int16_val(data, 5),
  367. int16_val(data, 4),
  368. -int16_val(data, 6));
  369. gyro *= _gyro_scale;
  370. _rotate_and_correct_accel(_accel_instance, accel);
  371. _rotate_and_correct_gyro(_gyro_instance, gyro);
  372. _notify_new_accel_raw_sample(_accel_instance, accel, 0, fsync_set);
  373. _notify_new_gyro_raw_sample(_gyro_instance, gyro);
  374. _temp_filtered = _temp_filter.apply(temp);
  375. }
  376. return true;
  377. }
  378. /*
  379. when doing fast sampling the sensor gives us 8k samples/second. Every 2nd accel sample is a duplicate.
  380. To filter this we first apply a 1p low pass filter at 188Hz, then we
  381. average over 8 samples to bring the data rate down to 1kHz. This
  382. gives very good aliasing rejection at frequencies well above what
  383. can be handled with 1kHz sample rates.
  384. */
  385. bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
  386. {
  387. int32_t tsum = 0;
  388. const int32_t unscaled_clip_limit = _clip_limit / _accel_scale;
  389. bool clipped = false;
  390. bool ret = true;
  391. for (uint8_t i = 0; i < n_samples; i++) {
  392. const uint8_t *data = samples + MPU_SAMPLE_SIZE * i;
  393. // use temperatue to detect FIFO corruption
  394. int16_t t2 = int16_val(data, 3);
  395. if (!_check_raw_temp(t2)) {
  396. debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
  397. _fifo_reset();
  398. ret = false;
  399. break;
  400. }
  401. tsum += t2;
  402. if ((_accum.count & 1) == 0) {
  403. // accel data is at 4kHz
  404. Vector3f a(int16_val(data, 1),
  405. int16_val(data, 0),
  406. -int16_val(data, 2));
  407. if (fabsf(a.x) > unscaled_clip_limit ||
  408. fabsf(a.y) > unscaled_clip_limit ||
  409. fabsf(a.z) > unscaled_clip_limit) {
  410. clipped = true;
  411. }
  412. _accum.accel += _accum.accel_filter.apply(a);
  413. Vector3f a2 = a * _accel_scale;
  414. _notify_new_accel_sensor_rate_sample(_accel_instance, a2);
  415. }
  416. Vector3f g(int16_val(data, 5),
  417. int16_val(data, 4),
  418. -int16_val(data, 6));
  419. Vector3f g2 = g * _gyro_scale;
  420. _notify_new_gyro_sensor_rate_sample(_gyro_instance, g2);
  421. _accum.gyro += _accum.gyro_filter.apply(g);
  422. _accum.count++;
  423. if (_accum.count == _fifo_downsample_rate) {
  424. _accum.accel *= _fifo_accel_scale;
  425. _accum.gyro *= _fifo_gyro_scale;
  426. _rotate_and_correct_accel(_accel_instance, _accum.accel);
  427. _rotate_and_correct_gyro(_gyro_instance, _accum.gyro);
  428. _notify_new_accel_raw_sample(_accel_instance, _accum.accel, 0, false);
  429. _notify_new_gyro_raw_sample(_gyro_instance, _accum.gyro);
  430. _accum.accel.zero();
  431. _accum.gyro.zero();
  432. _accum.count = 0;
  433. }
  434. }
  435. if (clipped) {
  436. increment_clip_count(_accel_instance);
  437. }
  438. if (ret) {
  439. float temp = (static_cast<float>(tsum)/n_samples)*temp_sensitivity + temp_zero;
  440. _temp_filtered = _temp_filter.apply(temp);
  441. }
  442. return ret;
  443. }
  444. void AP_InertialSensor_Invensense::_read_fifo()
  445. {
  446. uint8_t n_samples;
  447. uint16_t bytes_read;
  448. uint8_t *rx = _fifo_buffer;
  449. bool need_reset = false;
  450. if (!_block_read(MPUREG_FIFO_COUNTH, rx, 2)) {
  451. goto check_registers;
  452. }
  453. bytes_read = uint16_val(rx, 0);
  454. n_samples = bytes_read / MPU_SAMPLE_SIZE;
  455. if (n_samples == 0) {
  456. /* Not enough data in FIFO */
  457. goto check_registers;
  458. }
  459. /*
  460. testing has shown that if we have more than 32 samples in the
  461. FIFO then some of those samples will be corrupt. It always is
  462. the ones at the end of the FIFO, so clear those with a reset
  463. once we've read the first 24. Reading 24 gives us the normal
  464. number of samples for fast sampling at 400Hz
  465. On I2C with the much lower clock rates we need a lower threshold
  466. or we may never catch up
  467. */
  468. if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C) {
  469. if (n_samples > 4) {
  470. need_reset = true;
  471. n_samples = 4;
  472. }
  473. } else {
  474. if (n_samples > 32) {
  475. need_reset = true;
  476. n_samples = 24;
  477. }
  478. }
  479. while (n_samples > 0) {
  480. uint8_t n = MIN(n_samples, MPU_FIFO_BUFFER_LEN);
  481. if (!_dev->set_chip_select(true)) {
  482. if (!_block_read(MPUREG_FIFO_R_W, rx, n * MPU_SAMPLE_SIZE)) {
  483. goto check_registers;
  484. }
  485. } else {
  486. // this ensures we keep things nicely setup for DMA
  487. uint8_t reg = MPUREG_FIFO_R_W | 0x80;
  488. if (!_dev->transfer(&reg, 1, nullptr, 0)) {
  489. _dev->set_chip_select(false);
  490. goto check_registers;
  491. }
  492. memset(rx, 0, n * MPU_SAMPLE_SIZE);
  493. if (!_dev->transfer(rx, n * MPU_SAMPLE_SIZE, rx, n * MPU_SAMPLE_SIZE)) {
  494. hal.console->printf("MPU60x0: error in fifo read %u bytes\n", n * MPU_SAMPLE_SIZE);
  495. _dev->set_chip_select(false);
  496. goto check_registers;
  497. }
  498. _dev->set_chip_select(false);
  499. }
  500. if (_fast_sampling) {
  501. if (!_accumulate_sensor_rate_sampling(rx, n)) {
  502. debug("IMU[%u] stop at %u of %u", _accel_instance, n_samples, bytes_read/MPU_SAMPLE_SIZE);
  503. break;
  504. }
  505. } else {
  506. if (!_accumulate(rx, n)) {
  507. break;
  508. }
  509. }
  510. n_samples -= n;
  511. }
  512. if (need_reset) {
  513. //debug("fifo reset n_samples %u", bytes_read/MPU_SAMPLE_SIZE);
  514. _fifo_reset();
  515. }
  516. check_registers:
  517. // check next register value for correctness
  518. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  519. if (!_dev->check_next_register()) {
  520. _inc_gyro_error_count(_gyro_instance);
  521. _inc_accel_error_count(_accel_instance);
  522. }
  523. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  524. }
  525. /*
  526. fetch temperature in order to detect FIFO sync errors
  527. */
  528. bool AP_InertialSensor_Invensense::_check_raw_temp(int16_t t2)
  529. {
  530. if (abs(t2 - _raw_temp) < 400) {
  531. // cached copy OK
  532. return true;
  533. }
  534. uint8_t trx[2];
  535. if (_block_read(MPUREG_TEMP_OUT_H, trx, 2)) {
  536. _raw_temp = int16_val(trx, 0);
  537. }
  538. return (abs(t2 - _raw_temp) < 800);
  539. }
  540. bool AP_InertialSensor_Invensense::_block_read(uint8_t reg, uint8_t *buf,
  541. uint32_t size)
  542. {
  543. return _dev->read_registers(reg, buf, size);
  544. }
  545. uint8_t AP_InertialSensor_Invensense::_register_read(uint8_t reg)
  546. {
  547. uint8_t val = 0;
  548. _dev->read_registers(reg, &val, 1);
  549. return val;
  550. }
  551. void AP_InertialSensor_Invensense::_register_write(uint8_t reg, uint8_t val, bool checked)
  552. {
  553. _dev->write_register(reg, val, checked);
  554. }
  555. /*
  556. set the DLPF filter frequency. Assumes caller has taken semaphore
  557. */
  558. void AP_InertialSensor_Invensense::_set_filter_register(void)
  559. {
  560. uint8_t config;
  561. #if INVENSENSE_EXT_SYNC_ENABLE
  562. // add in EXT_SYNC bit if enabled
  563. config = (MPUREG_CONFIG_EXT_SYNC_AZ << MPUREG_CONFIG_EXT_SYNC_SHIFT);
  564. #else
  565. config = 0;
  566. #endif
  567. // assume 1kHz sampling to start
  568. _fifo_downsample_rate = 1;
  569. _backend_rate_hz = 1000;
  570. if (enable_fast_sampling(_accel_instance)) {
  571. _fast_sampling = (_mpu_type >= Invensense_MPU9250 && _dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI);
  572. if (_fast_sampling) {
  573. if (get_sample_rate_hz() <= 1000) {
  574. _fifo_downsample_rate = 8;
  575. } else if (get_sample_rate_hz() <= 2000) {
  576. _fifo_downsample_rate = 4;
  577. } else {
  578. _fifo_downsample_rate = 2;
  579. }
  580. // calculate rate we will be giving samples to the backend
  581. _backend_rate_hz *= (8 / _fifo_downsample_rate);
  582. // for logging purposes set the oversamping rate
  583. _set_accel_oversampling(_accel_instance, _fifo_downsample_rate/2);
  584. _set_gyro_oversampling(_gyro_instance, _fifo_downsample_rate);
  585. _set_accel_sensor_rate_sampling_enabled(_accel_instance, true);
  586. _set_gyro_sensor_rate_sampling_enabled(_gyro_instance, true);
  587. /* set divider for internal sample rate to 0x1F when fast
  588. sampling enabled. This reduces the impact of the slave
  589. sensor on the sample rate. It ends up with around 75Hz
  590. slave rate, and reduces the impact on the gyro and accel
  591. sample rate, ending up with around 7760Hz gyro rate and
  592. 3880Hz accel rate
  593. */
  594. _register_write(MPUREG_I2C_SLV4_CTRL, 0x1F);
  595. }
  596. }
  597. if (_fast_sampling) {
  598. // this gives us 8kHz sampling on gyros and 4kHz on accels
  599. config |= BITS_DLPF_CFG_256HZ_NOLPF2;
  600. } else {
  601. // limit to 1kHz if not on SPI
  602. config |= BITS_DLPF_CFG_188HZ;
  603. }
  604. config |= MPUREG_CONFIG_FIFO_MODE_STOP;
  605. _register_write(MPUREG_CONFIG, config, true);
  606. if (_mpu_type != Invensense_MPU6000) {
  607. if (_fast_sampling) {
  608. // setup for 4kHz accels
  609. _register_write(ICMREG_ACCEL_CONFIG2, ICM_ACC_FCHOICE_B, true);
  610. } else {
  611. uint8_t fifo_size = (_mpu_type == Invensense_ICM20789 || _mpu_type == Invensense_ICM20689) ? 1:0;
  612. _register_write(ICMREG_ACCEL_CONFIG2, ICM_ACC_DLPF_CFG_218HZ | (fifo_size<<6), true);
  613. }
  614. }
  615. }
  616. /*
  617. check whoami for sensor type
  618. */
  619. bool AP_InertialSensor_Invensense::_check_whoami(void)
  620. {
  621. uint8_t whoami = _register_read(MPUREG_WHOAMI);
  622. switch (whoami) {
  623. case MPU_WHOAMI_6000:
  624. _mpu_type = Invensense_MPU6000;
  625. return true;
  626. case MPU_WHOAMI_6500:
  627. _mpu_type = Invensense_MPU6500;
  628. return true;
  629. case MPU_WHOAMI_MPU9250:
  630. case MPU_WHOAMI_MPU9255:
  631. _mpu_type = Invensense_MPU9250;
  632. return true;
  633. case MPU_WHOAMI_20608:
  634. _mpu_type = Invensense_ICM20608;
  635. return true;
  636. case MPU_WHOAMI_20602:
  637. _mpu_type = Invensense_ICM20602;
  638. return true;
  639. case MPU_WHOAMI_20601:
  640. _mpu_type = Invensense_ICM20601;
  641. return true;
  642. case MPU_WHOAMI_ICM20789:
  643. case MPU_WHOAMI_ICM20789_R1:
  644. _mpu_type = Invensense_ICM20789;
  645. return true;
  646. case MPU_WHOAMI_ICM20689:
  647. _mpu_type = Invensense_ICM20689;
  648. return true;
  649. }
  650. // not a value WHOAMI result
  651. return false;
  652. }
  653. bool AP_InertialSensor_Invensense::_hardware_init(void)
  654. {
  655. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  656. return false;
  657. }
  658. // setup for register checking. We check much less often on I2C
  659. // where the cost of the checks is higher
  660. _dev->setup_checked_registers(7, _dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C?200:20);
  661. // initially run the bus at low speed
  662. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  663. if (!_check_whoami()) {
  664. _dev->get_semaphore()->give();
  665. return false;
  666. }
  667. // Chip reset
  668. uint8_t tries;
  669. for (tries = 0; tries < 5; tries++) {
  670. _last_stat_user_ctrl = _register_read(MPUREG_USER_CTRL);
  671. /* First disable the master I2C to avoid hanging the slaves on the
  672. * aulixiliar I2C bus - it will be enabled again if the AuxiliaryBus
  673. * is used */
  674. if (_last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN) {
  675. _last_stat_user_ctrl &= ~BIT_USER_CTRL_I2C_MST_EN;
  676. _register_write(MPUREG_USER_CTRL, _last_stat_user_ctrl);
  677. hal.scheduler->delay(10);
  678. }
  679. /* reset device */
  680. _register_write(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_DEVICE_RESET);
  681. hal.scheduler->delay(100);
  682. /* bus-dependent initialization */
  683. if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
  684. /* Disable I2C bus if SPI selected (Recommended in Datasheet to be
  685. * done just after the device is reset) */
  686. _last_stat_user_ctrl |= BIT_USER_CTRL_I2C_IF_DIS;
  687. _register_write(MPUREG_USER_CTRL, _last_stat_user_ctrl);
  688. }
  689. /* bus-dependent initialization */
  690. if ((_dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C) && (_mpu_type == Invensense_MPU9250 || _mpu_type == Invensense_ICM20789)) {
  691. /* Enable I2C bypass to access internal device */
  692. _register_write(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);
  693. }
  694. // Wake up device and select GyroZ clock. Note that the
  695. // Invensense starts up in sleep mode, and it can take some time
  696. // for it to come out of sleep
  697. _register_write(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_ZGYRO);
  698. hal.scheduler->delay(5);
  699. // check it has woken up
  700. if (_register_read(MPUREG_PWR_MGMT_1) == BIT_PWR_MGMT_1_CLK_ZGYRO) {
  701. break;
  702. }
  703. hal.scheduler->delay(10);
  704. if (_data_ready()) {
  705. break;
  706. }
  707. }
  708. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  709. if (tries == 5) {
  710. hal.console->printf("Failed to boot Invensense 5 times\n");
  711. _dev->get_semaphore()->give();
  712. return false;
  713. }
  714. if (_mpu_type == Invensense_ICM20608 ||
  715. _mpu_type == Invensense_ICM20602 ||
  716. _mpu_type == Invensense_ICM20601) {
  717. // this avoids a sensor bug, see description above
  718. _register_write(MPUREG_ICM_UNDOC1, MPUREG_ICM_UNDOC1_VALUE, true);
  719. }
  720. _dev->get_semaphore()->give();
  721. return true;
  722. }
  723. AP_Invensense_AuxiliaryBusSlave::AP_Invensense_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr,
  724. uint8_t instance)
  725. : AuxiliaryBusSlave(bus, addr, instance)
  726. , _mpu_addr(MPUREG_I2C_SLV0_ADDR + _instance * 3)
  727. , _mpu_reg(_mpu_addr + 1)
  728. , _mpu_ctrl(_mpu_addr + 2)
  729. , _mpu_do(MPUREG_I2C_SLV0_DO + _instance)
  730. {
  731. }
  732. int AP_Invensense_AuxiliaryBusSlave::_set_passthrough(uint8_t reg, uint8_t size,
  733. uint8_t *out)
  734. {
  735. auto &backend = AP_InertialSensor_Invensense::from(_bus.get_backend());
  736. uint8_t addr;
  737. /* Ensure the slave read/write is disabled before changing the registers */
  738. backend._register_write(_mpu_ctrl, 0);
  739. if (out) {
  740. backend._register_write(_mpu_do, *out);
  741. addr = _addr;
  742. } else {
  743. addr = _addr | BIT_READ_FLAG;
  744. }
  745. backend._register_write(_mpu_addr, addr);
  746. backend._register_write(_mpu_reg, reg);
  747. backend._register_write(_mpu_ctrl, BIT_I2C_SLVX_EN | size);
  748. return 0;
  749. }
  750. int AP_Invensense_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf,
  751. uint8_t size)
  752. {
  753. assert(buf);
  754. if (_registered) {
  755. hal.console->printf("Error: can't passthrough when slave is already configured\n");
  756. return -1;
  757. }
  758. int r = _set_passthrough(reg, size);
  759. if (r < 0) {
  760. return r;
  761. }
  762. /* wait the value to be read from the slave and read it back */
  763. hal.scheduler->delay(10);
  764. auto &backend = AP_InertialSensor_Invensense::from(_bus.get_backend());
  765. if (!backend._block_read(MPUREG_EXT_SENS_DATA_00 + _ext_sens_data, buf, size)) {
  766. return -1;
  767. }
  768. /* disable new reads */
  769. backend._register_write(_mpu_ctrl, 0);
  770. return size;
  771. }
  772. int AP_Invensense_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val)
  773. {
  774. if (_registered) {
  775. hal.console->printf("Error: can't passthrough when slave is already configured\n");
  776. return -1;
  777. }
  778. int r = _set_passthrough(reg, 1, &val);
  779. if (r < 0) {
  780. return r;
  781. }
  782. /* wait the value to be written to the slave */
  783. hal.scheduler->delay(10);
  784. auto &backend = AP_InertialSensor_Invensense::from(_bus.get_backend());
  785. /* disable new writes */
  786. backend._register_write(_mpu_ctrl, 0);
  787. return 1;
  788. }
  789. int AP_Invensense_AuxiliaryBusSlave::read(uint8_t *buf)
  790. {
  791. if (!_registered) {
  792. hal.console->printf("Error: can't read before configuring slave\n");
  793. return -1;
  794. }
  795. auto &backend = AP_InertialSensor_Invensense::from(_bus.get_backend());
  796. if (!backend._block_read(MPUREG_EXT_SENS_DATA_00 + _ext_sens_data, buf, _sample_size)) {
  797. return -1;
  798. }
  799. return _sample_size;
  800. }
  801. /* Invensense provides up to 5 slave devices, but the 5th is way too different to
  802. * configure and is seldom used */
  803. AP_Invensense_AuxiliaryBus::AP_Invensense_AuxiliaryBus(AP_InertialSensor_Invensense &backend, uint32_t devid)
  804. : AuxiliaryBus(backend, 4, devid)
  805. {
  806. }
  807. AP_HAL::Semaphore *AP_Invensense_AuxiliaryBus::get_semaphore()
  808. {
  809. return static_cast<AP_InertialSensor_Invensense&>(_ins_backend)._dev->get_semaphore();
  810. }
  811. AuxiliaryBusSlave *AP_Invensense_AuxiliaryBus::_instantiate_slave(uint8_t addr, uint8_t instance)
  812. {
  813. /* Enable slaves on Invensense if this is the first time */
  814. if (_ext_sens_data == 0) {
  815. _configure_slaves();
  816. }
  817. return new AP_Invensense_AuxiliaryBusSlave(*this, addr, instance);
  818. }
  819. void AP_Invensense_AuxiliaryBus::_configure_slaves()
  820. {
  821. auto &backend = AP_InertialSensor_Invensense::from(_ins_backend);
  822. if (backend._mpu_type == AP_InertialSensor_Invensense::Invensense_ICM20789) {
  823. // on 20789 we can't enable slaves if we want to be able to use the baro
  824. return;
  825. }
  826. if (!backend._dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  827. return;
  828. }
  829. /* Enable the I2C master to slaves on the auxiliary I2C bus*/
  830. if (!(backend._last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN)) {
  831. backend._last_stat_user_ctrl |= BIT_USER_CTRL_I2C_MST_EN;
  832. backend._register_write(MPUREG_USER_CTRL, backend._last_stat_user_ctrl);
  833. }
  834. /* stop condition between reads; clock at 400kHz */
  835. backend._register_write(MPUREG_I2C_MST_CTRL,
  836. BIT_I2C_MST_P_NSR | BIT_I2C_MST_CLK_400KHZ);
  837. /* Hard-code divider for internal sample rate, 1 kHz, resulting in a
  838. * sample rate of 100Hz */
  839. backend._register_write(MPUREG_I2C_SLV4_CTRL, 9);
  840. /* All slaves are subject to the sample rate */
  841. backend._register_write(MPUREG_I2C_MST_DELAY_CTRL,
  842. BIT_I2C_SLV0_DLY_EN | BIT_I2C_SLV1_DLY_EN |
  843. BIT_I2C_SLV2_DLY_EN | BIT_I2C_SLV3_DLY_EN);
  844. backend._dev->get_semaphore()->give();
  845. }
  846. int AP_Invensense_AuxiliaryBus::_configure_periodic_read(AuxiliaryBusSlave *slave,
  847. uint8_t reg, uint8_t size)
  848. {
  849. if (_ext_sens_data + size > MAX_EXT_SENS_DATA) {
  850. return -1;
  851. }
  852. AP_Invensense_AuxiliaryBusSlave *mpu_slave =
  853. static_cast<AP_Invensense_AuxiliaryBusSlave*>(slave);
  854. mpu_slave->_set_passthrough(reg, size);
  855. mpu_slave->_ext_sens_data = _ext_sens_data;
  856. _ext_sens_data += size;
  857. return 0;
  858. }
  859. AP_HAL::Device::PeriodicHandle AP_Invensense_AuxiliaryBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  860. {
  861. auto &backend = AP_InertialSensor_Invensense::from(_ins_backend);
  862. return backend._dev->register_periodic_callback(period_usec, cb);
  863. }