AP_InertialSensor_Invensensev2.cpp 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884
  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 Invensensev2 IMUs
  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_Invensensev2.h"
  22. extern const AP_HAL::HAL& hal;
  23. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  24. // hal.console can be accessed from bus threads on ChibiOS
  25. #define debug(fmt, args ...) do {hal.console->printf("INV2: " fmt "\n", ## args); } while(0)
  26. #else
  27. #define debug(fmt, args ...) do {printf("INV2: " fmt "\n", ## args); } while(0)
  28. #endif
  29. /*
  30. * DS-000189-ICM-20948-v1.3.pdf, page 11, section 3.1 lists LSB sensitivity of
  31. * gyro as 16.4 LSB/DPS at scale factor of +/- 2000dps (FS_SEL==3)
  32. */
  33. static const float GYRO_SCALE = (0.0174532f / 16.4f);
  34. /*
  35. EXT_SYNC allows for frame synchronisation with an external device
  36. such as a camera. When enabled the LSB of AccelZ holds the FSYNC bit
  37. */
  38. #ifndef INVENSENSE_EXT_SYNC_ENABLE
  39. #define INVENSENSE_EXT_SYNC_ENABLE 0
  40. #endif
  41. #include "AP_InertialSensor_Invensensev2_registers.h"
  42. #define INV2_SAMPLE_SIZE 14
  43. #define INV2_FIFO_BUFFER_LEN 16
  44. #define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]))
  45. #define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])
  46. AP_InertialSensor_Invensensev2::AP_InertialSensor_Invensensev2(AP_InertialSensor &imu,
  47. AP_HAL::OwnPtr<AP_HAL::Device> dev,
  48. enum Rotation rotation)
  49. : AP_InertialSensor_Backend(imu)
  50. , _temp_filter(1125, 1)
  51. , _rotation(rotation)
  52. , _dev(std::move(dev))
  53. {
  54. }
  55. AP_InertialSensor_Invensensev2::~AP_InertialSensor_Invensensev2()
  56. {
  57. if (_fifo_buffer != nullptr) {
  58. hal.util->free_type(_fifo_buffer, INV2_FIFO_BUFFER_LEN * INV2_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE);
  59. }
  60. //delete _auxiliary_bus;
  61. }
  62. AP_InertialSensor_Backend *AP_InertialSensor_Invensensev2::probe(AP_InertialSensor &imu,
  63. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  64. enum Rotation rotation)
  65. {
  66. if (!dev) {
  67. return nullptr;
  68. }
  69. AP_InertialSensor_Invensensev2 *sensor =
  70. new AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation);
  71. if (!sensor || !sensor->_init()) {
  72. delete sensor;
  73. return nullptr;
  74. }
  75. sensor->_id = HAL_INS_INV2_I2C;
  76. return sensor;
  77. }
  78. AP_InertialSensor_Backend *AP_InertialSensor_Invensensev2::probe(AP_InertialSensor &imu,
  79. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev,
  80. enum Rotation rotation)
  81. {
  82. if (!dev) {
  83. return nullptr;
  84. }
  85. AP_InertialSensor_Invensensev2 *sensor;
  86. dev->set_read_flag(0x80);
  87. sensor = new AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation);
  88. if (!sensor || !sensor->_init()) {
  89. delete sensor;
  90. return nullptr;
  91. }
  92. sensor->_id = HAL_INS_INV2_SPI;
  93. return sensor;
  94. }
  95. bool AP_InertialSensor_Invensensev2::_init()
  96. {
  97. #ifdef INVENSENSEV2_DRDY_PIN
  98. _drdy_pin = hal.gpio->channel(INVENSENSEV2_DRDY_PIN);
  99. _drdy_pin->mode(HAL_GPIO_INPUT);
  100. #endif
  101. bool success = _hardware_init();
  102. return success;
  103. }
  104. void AP_InertialSensor_Invensensev2::_fifo_reset()
  105. {
  106. uint8_t user_ctrl = _last_stat_user_ctrl;
  107. user_ctrl &= ~(BIT_USER_CTRL_FIFO_EN);
  108. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  109. _register_write(INV2REG_FIFO_EN_2, 0);
  110. _register_write(INV2REG_USER_CTRL, user_ctrl);
  111. _register_write(INV2REG_FIFO_RST, 0x0F);
  112. _register_write(INV2REG_FIFO_RST, 0x00);
  113. _register_write(INV2REG_USER_CTRL, user_ctrl | BIT_USER_CTRL_FIFO_EN);
  114. _register_write(INV2REG_FIFO_EN_2, BIT_XG_FIFO_EN | BIT_YG_FIFO_EN |
  115. BIT_ZG_FIFO_EN | BIT_ACCEL_FIFO_EN | BIT_TEMP_FIFO_EN, true);
  116. hal.scheduler->delay_microseconds(1);
  117. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  118. _last_stat_user_ctrl = user_ctrl | BIT_USER_CTRL_FIFO_EN;
  119. notify_accel_fifo_reset(_accel_instance);
  120. notify_gyro_fifo_reset(_gyro_instance);
  121. }
  122. bool AP_InertialSensor_Invensensev2::_has_auxiliary_bus()
  123. {
  124. return _dev->bus_type() != AP_HAL::Device::BUS_TYPE_I2C;
  125. }
  126. void AP_InertialSensor_Invensensev2::start()
  127. {
  128. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  129. return;
  130. }
  131. // initially run the bus at low speed
  132. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  133. // only used for wake-up in accelerometer only low power mode
  134. _register_write(INV2REG_PWR_MGMT_2, 0x00);
  135. hal.scheduler->delay(1);
  136. // always use FIFO
  137. _fifo_reset();
  138. // grab the used instances
  139. enum DevTypes gdev, adev;
  140. switch (_inv2_type) {
  141. case Invensensev2_ICM20648:
  142. gdev = DEVTYPE_INS_ICM20648;
  143. adev = DEVTYPE_INS_ICM20648;
  144. // using 16g full range, 2048 LSB/g
  145. _accel_scale = (GRAVITY_MSS / 2048);
  146. break;
  147. case Invensensev2_ICM20649:
  148. // 20649 is setup for 30g full scale, 1024 LSB/g
  149. gdev = DEVTYPE_INS_ICM20649;
  150. adev = DEVTYPE_INS_ICM20649;
  151. _accel_scale = (GRAVITY_MSS / 1024);
  152. break;
  153. case Invensensev2_ICM20948:
  154. default:
  155. gdev = DEVTYPE_INS_ICM20948;
  156. adev = DEVTYPE_INS_ICM20948;
  157. // using 16g full range, 2048 LSB/g
  158. _accel_scale = (GRAVITY_MSS / 2048);
  159. break;
  160. }
  161. _gyro_instance = _imu.register_gyro(1125, _dev->get_bus_id_devtype(gdev));
  162. _accel_instance = _imu.register_accel(1125, _dev->get_bus_id_devtype(adev));
  163. // setup on-sensor filtering and scaling
  164. _set_filter_and_scaling();
  165. #if INVENSENSE_EXT_SYNC_ENABLE
  166. _register_write(INV2REG_FSYNC_CONFIG, FSYNC_CONFIG_EXT_SYNC_AZ, true);
  167. #endif
  168. // update backend sample rate
  169. _set_accel_raw_sample_rate(_accel_instance, _backend_rate_hz);
  170. _set_gyro_raw_sample_rate(_gyro_instance, _backend_rate_hz);
  171. // indicate what multiplier is appropriate for the sensors'
  172. // readings to fit them into an int16_t:
  173. _set_raw_sample_accel_multiplier(_accel_instance, multiplier_accel);
  174. if (_fast_sampling) {
  175. hal.console->printf("INV2[%u]: enabled fast sampling rate %uHz/%uHz\n",
  176. _accel_instance, _backend_rate_hz*_fifo_downsample_rate, _backend_rate_hz);
  177. }
  178. // set sample rate to 1.125KHz
  179. _register_write(INV2REG_GYRO_SMPLRT_DIV, 0, true);
  180. hal.scheduler->delay(1);
  181. // configure interrupt to fire when new data arrives
  182. _register_write(INV2REG_INT_ENABLE_1, 0x01);
  183. hal.scheduler->delay(1);
  184. // now that we have initialised, we set the bus speed to high
  185. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  186. _dev->get_semaphore()->give();
  187. // setup sensor rotations from probe()
  188. set_gyro_orientation(_gyro_instance, _rotation);
  189. set_accel_orientation(_accel_instance, _rotation);
  190. // setup scale factors for fifo data after downsampling
  191. _fifo_accel_scale = _accel_scale / (MAX(_fifo_downsample_rate,2)/2);
  192. _fifo_gyro_scale = GYRO_SCALE / _fifo_downsample_rate;
  193. // allocate fifo buffer
  194. _fifo_buffer = (uint8_t *)hal.util->malloc_type(INV2_FIFO_BUFFER_LEN * INV2_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE);
  195. if (_fifo_buffer == nullptr) {
  196. AP_HAL::panic("Invensense: Unable to allocate FIFO buffer");
  197. }
  198. // start the timer process to read samples
  199. _dev->register_periodic_callback(1265625UL / _backend_rate_hz, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Invensensev2::_poll_data, void));
  200. }
  201. /*
  202. publish any pending data
  203. */
  204. bool AP_InertialSensor_Invensensev2::update()
  205. {
  206. update_accel(_accel_instance);
  207. update_gyro(_gyro_instance);
  208. _publish_temperature(_accel_instance, _temp_filtered);
  209. return true;
  210. }
  211. /*
  212. accumulate new samples
  213. */
  214. void AP_InertialSensor_Invensensev2::accumulate()
  215. {
  216. // nothing to do
  217. }
  218. AuxiliaryBus *AP_InertialSensor_Invensensev2::get_auxiliary_bus()
  219. {
  220. if (_auxiliary_bus) {
  221. return _auxiliary_bus;
  222. }
  223. if (_has_auxiliary_bus()) {
  224. _auxiliary_bus = new AP_Invensensev2_AuxiliaryBus(*this, _dev->get_bus_id());
  225. }
  226. return _auxiliary_bus;
  227. }
  228. /*
  229. * Return true if the Invensense has new data available for reading.
  230. *
  231. * We use the data ready pin if it is available. Otherwise, read the
  232. * status register.
  233. */
  234. bool AP_InertialSensor_Invensensev2::_data_ready()
  235. {
  236. if (_drdy_pin) {
  237. return _drdy_pin->read() != 0;
  238. }
  239. uint8_t status = _register_read(INV2REG_INT_STATUS_1);
  240. return status != 0;
  241. }
  242. /*
  243. * Timer process to poll for new data from the Invensense. Called from bus thread with semaphore held
  244. */
  245. void AP_InertialSensor_Invensensev2::_poll_data()
  246. {
  247. _read_fifo();
  248. }
  249. bool AP_InertialSensor_Invensensev2::_accumulate(uint8_t *samples, uint8_t n_samples)
  250. {
  251. for (uint8_t i = 0; i < n_samples; i++) {
  252. const uint8_t *data = samples + INV2_SAMPLE_SIZE * i;
  253. Vector3f accel, gyro;
  254. bool fsync_set = false;
  255. #if INVENSENSE_EXT_SYNC_ENABLE
  256. fsync_set = (int16_val(data, 2) & 1U) != 0;
  257. #endif
  258. accel = Vector3f(int16_val(data, 1),
  259. int16_val(data, 0),
  260. -int16_val(data, 2));
  261. accel *= _accel_scale;
  262. int16_t t2 = int16_val(data, 6);
  263. if (!_check_raw_temp(t2)) {
  264. debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
  265. _fifo_reset();
  266. return false;
  267. }
  268. float temp = t2 * temp_sensitivity + temp_zero;
  269. gyro = Vector3f(int16_val(data, 4),
  270. int16_val(data, 3),
  271. -int16_val(data, 5));
  272. gyro *= GYRO_SCALE;
  273. _rotate_and_correct_accel(_accel_instance, accel);
  274. _rotate_and_correct_gyro(_gyro_instance, gyro);
  275. _notify_new_accel_raw_sample(_accel_instance, accel, 0, fsync_set);
  276. _notify_new_gyro_raw_sample(_gyro_instance, gyro);
  277. _temp_filtered = _temp_filter.apply(temp);
  278. }
  279. return true;
  280. }
  281. /*
  282. when doing fast sampling the sensor gives us 9k samples/second. Every 2nd accel sample is a duplicate.
  283. To filter this we first apply a 1p low pass filter at 188Hz, then we
  284. average over 8 samples to bring the data rate down to 1kHz. This
  285. gives very good aliasing rejection at frequencies well above what
  286. can be handled with 1kHz sample rates.
  287. */
  288. bool AP_InertialSensor_Invensensev2::_accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
  289. {
  290. int32_t tsum = 0;
  291. int32_t unscaled_clip_limit = _clip_limit / _accel_scale;
  292. bool clipped = false;
  293. bool ret = true;
  294. for (uint8_t i = 0; i < n_samples; i++) {
  295. const uint8_t *data = samples + INV2_SAMPLE_SIZE * i;
  296. // use temperature to detect FIFO corruption
  297. int16_t t2 = int16_val(data, 6);
  298. if (!_check_raw_temp(t2)) {
  299. debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
  300. _fifo_reset();
  301. ret = false;
  302. break;
  303. }
  304. tsum += t2;
  305. // accel data is at 4kHz
  306. if ((_accum.count & 1) == 0) {
  307. Vector3f a(int16_val(data, 1),
  308. int16_val(data, 0),
  309. -int16_val(data, 2));
  310. if (fabsf(a.x) > unscaled_clip_limit ||
  311. fabsf(a.y) > unscaled_clip_limit ||
  312. fabsf(a.z) > unscaled_clip_limit) {
  313. clipped = true;
  314. }
  315. _accum.accel += _accum.accel_filter.apply(a);
  316. Vector3f a2 = a * _accel_scale;
  317. _notify_new_accel_sensor_rate_sample(_accel_instance, a2);
  318. }
  319. Vector3f g(int16_val(data, 4),
  320. int16_val(data, 3),
  321. -int16_val(data, 5));
  322. Vector3f g2 = g * GYRO_SCALE;
  323. _notify_new_gyro_sensor_rate_sample(_gyro_instance, g2);
  324. _accum.gyro += _accum.gyro_filter.apply(g);
  325. _accum.count++;
  326. if (_accum.count == _fifo_downsample_rate) {
  327. _accum.accel *= _fifo_accel_scale;
  328. _accum.gyro *= _fifo_gyro_scale;
  329. _rotate_and_correct_accel(_accel_instance, _accum.accel);
  330. _rotate_and_correct_gyro(_gyro_instance, _accum.gyro);
  331. _notify_new_accel_raw_sample(_accel_instance, _accum.accel, 0, false);
  332. _notify_new_gyro_raw_sample(_gyro_instance, _accum.gyro);
  333. _accum.accel.zero();
  334. _accum.gyro.zero();
  335. _accum.count = 0;
  336. }
  337. }
  338. if (clipped) {
  339. increment_clip_count(_accel_instance);
  340. }
  341. if (ret) {
  342. float temp = (static_cast<float>(tsum)/n_samples)*temp_sensitivity + temp_zero;
  343. _temp_filtered = _temp_filter.apply(temp);
  344. }
  345. return ret;
  346. }
  347. void AP_InertialSensor_Invensensev2::_read_fifo()
  348. {
  349. uint8_t n_samples;
  350. uint16_t bytes_read;
  351. uint8_t *rx = _fifo_buffer;
  352. bool need_reset = false;
  353. if (!_block_read(INV2REG_FIFO_COUNTH, rx, 2)) {
  354. goto check_registers;
  355. }
  356. bytes_read = uint16_val(rx, 0);
  357. n_samples = bytes_read / INV2_SAMPLE_SIZE;
  358. if (n_samples == 0) {
  359. /* Not enough data in FIFO */
  360. goto check_registers;
  361. }
  362. /*
  363. testing has shown that if we have more than 32 samples in the
  364. FIFO then some of those samples will be corrupt. It always is
  365. the ones at the end of the FIFO, so clear those with a reset
  366. once we've read the first 24. Reading 24 gives us the normal
  367. number of samples for fast sampling at 400Hz
  368. On I2C with the much lower clock rates we need a lower threshold
  369. or we may never catch up
  370. */
  371. if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C) {
  372. if (n_samples > 4) {
  373. need_reset = true;
  374. n_samples = 4;
  375. }
  376. } else {
  377. if (n_samples > 32) {
  378. need_reset = true;
  379. n_samples = 24;
  380. }
  381. }
  382. while (n_samples > 0) {
  383. uint8_t n = MIN(n_samples, INV2_FIFO_BUFFER_LEN);
  384. if (!_dev->set_chip_select(true)) {
  385. if (!_block_read(INV2REG_FIFO_R_W, rx, n * INV2_SAMPLE_SIZE)) {
  386. goto check_registers;
  387. }
  388. } else {
  389. // this ensures we keep things nicely setup for DMA
  390. _select_bank(GET_BANK(INV2REG_FIFO_R_W));
  391. uint8_t reg = GET_REG(INV2REG_FIFO_R_W) | 0x80;
  392. if (!_dev->transfer(&reg, 1, nullptr, 0)) {
  393. _dev->set_chip_select(false);
  394. goto check_registers;
  395. }
  396. memset(rx, 0, n * INV2_SAMPLE_SIZE);
  397. if (!_dev->transfer(rx, n * INV2_SAMPLE_SIZE, rx, n * INV2_SAMPLE_SIZE)) {
  398. hal.console->printf("INV2: error in fifo read %u bytes\n", n * INV2_SAMPLE_SIZE);
  399. _dev->set_chip_select(false);
  400. goto check_registers;
  401. }
  402. _dev->set_chip_select(false);
  403. }
  404. if (_fast_sampling) {
  405. if (!_accumulate_sensor_rate_sampling(rx, n)) {
  406. debug("IMU[%u] stop at %u of %u", _accel_instance, n_samples, bytes_read/INV2_SAMPLE_SIZE);
  407. break;
  408. }
  409. } else {
  410. if (!_accumulate(rx, n)) {
  411. break;
  412. }
  413. }
  414. n_samples -= n;
  415. }
  416. if (need_reset) {
  417. //debug("fifo reset n_samples %u", bytes_read/INV2_SAMPLE_SIZE);
  418. _fifo_reset();
  419. }
  420. check_registers:
  421. // check next register value for correctness
  422. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  423. if (!_dev->check_next_register()) {
  424. _inc_gyro_error_count(_gyro_instance);
  425. _inc_accel_error_count(_accel_instance);
  426. }
  427. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  428. }
  429. /*
  430. fetch temperature in order to detect FIFO sync errors
  431. */
  432. bool AP_InertialSensor_Invensensev2::_check_raw_temp(int16_t t2)
  433. {
  434. if (abs(t2 - _raw_temp) < 400) {
  435. // cached copy OK
  436. return true;
  437. }
  438. uint8_t trx[2];
  439. if (_block_read(INV2REG_TEMP_OUT_H, trx, 2)) {
  440. _raw_temp = int16_val(trx, 0);
  441. }
  442. return (abs(t2 - _raw_temp) < 400);
  443. }
  444. bool AP_InertialSensor_Invensensev2::_block_read(uint16_t reg, uint8_t *buf,
  445. uint32_t size)
  446. {
  447. _select_bank(GET_BANK(reg));
  448. return _dev->read_registers(reg, buf, size);
  449. }
  450. uint8_t AP_InertialSensor_Invensensev2::_register_read(uint16_t reg)
  451. {
  452. uint8_t val = 0;
  453. _select_bank(GET_BANK(reg));
  454. _dev->read_registers(GET_REG(reg), &val, 1);
  455. return val;
  456. }
  457. void AP_InertialSensor_Invensensev2::_register_write(uint16_t reg, uint8_t val, bool checked)
  458. {
  459. (void)checked;
  460. _select_bank(GET_BANK(reg));
  461. _dev->write_register(GET_REG(reg), val, false);
  462. }
  463. void AP_InertialSensor_Invensensev2::_select_bank(uint8_t bank)
  464. {
  465. if (_current_bank != bank) {
  466. _dev->write_register(INV2REG_BANK_SEL, bank << 4, true);
  467. _current_bank = bank;
  468. }
  469. }
  470. /*
  471. set the DLPF filter frequency and Gyro Accel Scaling. Assumes caller has taken semaphore
  472. */
  473. void AP_InertialSensor_Invensensev2::_set_filter_and_scaling(void)
  474. {
  475. uint8_t gyro_config = (_inv2_type == Invensensev2_ICM20649)?BITS_GYRO_FS_2000DPS_20649 : BITS_GYRO_FS_2000DPS;
  476. uint8_t accel_config = (_inv2_type == Invensensev2_ICM20649)?BITS_ACCEL_FS_30G_20649:BITS_ACCEL_FS_16G;
  477. // assume 1.125kHz sampling to start
  478. _fifo_downsample_rate = 1;
  479. _backend_rate_hz = 1125;
  480. if (enable_fast_sampling(_accel_instance)) {
  481. _fast_sampling = _dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI;
  482. if (_fast_sampling) {
  483. if (get_sample_rate_hz() <= 1125) {
  484. _fifo_downsample_rate = 8;
  485. } else if (get_sample_rate_hz() <= 2250) {
  486. _fifo_downsample_rate = 4;
  487. } else {
  488. _fifo_downsample_rate = 2;
  489. }
  490. // calculate rate we will be giving samples to the backend
  491. _backend_rate_hz *= (8 / _fifo_downsample_rate);
  492. // for logging purposes set the oversamping rate
  493. _set_accel_oversampling(_accel_instance, _fifo_downsample_rate/2);
  494. _set_gyro_oversampling(_gyro_instance, _fifo_downsample_rate);
  495. _set_accel_sensor_rate_sampling_enabled(_accel_instance, true);
  496. _set_gyro_sensor_rate_sampling_enabled(_gyro_instance, true);
  497. /* set divider for internal sample rate to 0x1F when fast
  498. sampling enabled. This reduces the impact of the slave
  499. sensor on the sample rate.
  500. */
  501. _register_write(INV2REG_I2C_SLV4_CTRL, 0x1F);
  502. }
  503. }
  504. if (_fast_sampling) {
  505. // this gives us 9kHz sampling on gyros
  506. gyro_config |= BIT_GYRO_NODLPF_9KHZ;
  507. accel_config |= BIT_ACCEL_NODLPF_4_5KHZ;
  508. } else {
  509. // limit to 1.125kHz if not on SPI
  510. gyro_config |= BIT_GYRO_DLPF_ENABLE | (GYRO_DLPF_CFG_188HZ << GYRO_DLPF_CFG_SHIFT);
  511. accel_config |= BIT_ACCEL_DLPF_ENABLE | (ACCEL_DLPF_CFG_265HZ << ACCEL_DLPF_CFG_SHIFT);
  512. }
  513. _register_write(INV2REG_GYRO_CONFIG_1, gyro_config, true);
  514. _register_write(INV2REG_ACCEL_CONFIG, accel_config, true);
  515. _register_write(INV2REG_FIFO_MODE, 0xF, true);
  516. }
  517. /*
  518. check whoami for sensor type
  519. */
  520. bool AP_InertialSensor_Invensensev2::_check_whoami(void)
  521. {
  522. uint8_t whoami = _register_read(INV2REG_WHO_AM_I);
  523. switch (whoami) {
  524. case INV2_WHOAMI_ICM20648:
  525. _inv2_type = Invensensev2_ICM20648;
  526. return true;
  527. case INV2_WHOAMI_ICM20948:
  528. _inv2_type = Invensensev2_ICM20948;
  529. return true;
  530. case INV2_WHOAMI_ICM20649:
  531. _inv2_type = Invensensev2_ICM20649;
  532. return true;
  533. }
  534. // not a value WHOAMI result
  535. return false;
  536. }
  537. bool AP_InertialSensor_Invensensev2::_hardware_init(void)
  538. {
  539. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  540. return false;
  541. }
  542. // disabled setup of checked registers as it can't cope with bank switching
  543. // _dev->setup_checked_registers(7, _dev->bus_type() == AP_HAL::Device::BUS_TYPE_I2C?200:20);
  544. // initially run the bus at low speed
  545. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  546. if (!_check_whoami()) {
  547. _dev->get_semaphore()->give();
  548. return false;
  549. }
  550. // Chip reset
  551. uint8_t tries;
  552. for (tries = 0; tries < 5; tries++) {
  553. _last_stat_user_ctrl = _register_read(INV2REG_USER_CTRL);
  554. /* First disable the master I2C to avoid hanging the slaves on the
  555. * aulixiliar I2C bus - it will be enabled again if the AuxiliaryBus
  556. * is used */
  557. if (_last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN) {
  558. _last_stat_user_ctrl &= ~BIT_USER_CTRL_I2C_MST_EN;
  559. _register_write(INV2REG_USER_CTRL, _last_stat_user_ctrl);
  560. hal.scheduler->delay(10);
  561. }
  562. /* reset device */
  563. _register_write(INV2REG_PWR_MGMT_1, BIT_PWR_MGMT_1_DEVICE_RESET);
  564. hal.scheduler->delay(100);
  565. /* bus-dependent initialization */
  566. if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
  567. /* Disable I2C bus if SPI selected (Recommended in Datasheet to be
  568. * done just after the device is reset) */
  569. _last_stat_user_ctrl |= BIT_USER_CTRL_I2C_IF_DIS;
  570. _register_write(INV2REG_USER_CTRL, _last_stat_user_ctrl);
  571. }
  572. // Wake up device and select Auto clock. Note that the
  573. // Invensense starts up in sleep mode, and it can take some time
  574. // for it to come out of sleep
  575. _register_write(INV2REG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_AUTO);
  576. hal.scheduler->delay(5);
  577. // check it has woken up
  578. if (_register_read(INV2REG_PWR_MGMT_1) == BIT_PWR_MGMT_1_CLK_AUTO) {
  579. break;
  580. }
  581. hal.scheduler->delay(10);
  582. if (_data_ready()) {
  583. break;
  584. }
  585. }
  586. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  587. if (tries == 5) {
  588. hal.console->printf("Failed to boot Invensense 5 times\n");
  589. _dev->get_semaphore()->give();
  590. return false;
  591. }
  592. if (_inv2_type == Invensensev2_ICM20649) {
  593. _clip_limit = 29.5f * GRAVITY_MSS;
  594. }
  595. _dev->get_semaphore()->give();
  596. return true;
  597. }
  598. AP_Invensensev2_AuxiliaryBusSlave::AP_Invensensev2_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr,
  599. uint8_t instance)
  600. : AuxiliaryBusSlave(bus, addr, instance)
  601. , _inv2_addr(INV2REG_I2C_SLV0_ADDR + _instance * 4)
  602. , _inv2_reg(_inv2_addr + 1)
  603. , _inv2_ctrl(_inv2_addr + 2)
  604. , _inv2_do(_inv2_addr + 3)
  605. {
  606. }
  607. int AP_Invensensev2_AuxiliaryBusSlave::_set_passthrough(uint8_t reg, uint8_t size,
  608. uint8_t *out)
  609. {
  610. auto &backend = AP_InertialSensor_Invensensev2::from(_bus.get_backend());
  611. uint8_t addr;
  612. /* Ensure the slave read/write is disabled before changing the registers */
  613. backend._register_write(_inv2_ctrl, 0);
  614. if (out) {
  615. backend._register_write(_inv2_do, *out);
  616. addr = _addr;
  617. } else {
  618. addr = _addr | BIT_READ_FLAG;
  619. }
  620. backend._register_write(_inv2_addr, addr);
  621. backend._register_write(_inv2_reg, reg);
  622. backend._register_write(_inv2_ctrl, BIT_I2C_SLVX_EN | size);
  623. return 0;
  624. }
  625. int AP_Invensensev2_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf,
  626. uint8_t size)
  627. {
  628. assert(buf);
  629. if (_registered) {
  630. hal.console->printf("Error: can't passthrough when slave is already configured\n");
  631. return -1;
  632. }
  633. int r = _set_passthrough(reg, size);
  634. if (r < 0) {
  635. return r;
  636. }
  637. /* wait the value to be read from the slave and read it back */
  638. hal.scheduler->delay(10);
  639. auto &backend = AP_InertialSensor_Invensensev2::from(_bus.get_backend());
  640. if (!backend._block_read(INV2REG_EXT_SLV_SENS_DATA_00 + _ext_sens_data, buf, size)) {
  641. return -1;
  642. }
  643. /* disable new reads */
  644. backend._register_write(_inv2_ctrl, 0);
  645. return size;
  646. }
  647. int AP_Invensensev2_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val)
  648. {
  649. if (_registered) {
  650. hal.console->printf("Error: can't passthrough when slave is already configured\n");
  651. return -1;
  652. }
  653. int r = _set_passthrough(reg, 1, &val);
  654. if (r < 0) {
  655. return r;
  656. }
  657. /* wait the value to be written to the slave */
  658. hal.scheduler->delay(10);
  659. auto &backend = AP_InertialSensor_Invensensev2::from(_bus.get_backend());
  660. /* disable new writes */
  661. backend._register_write(_inv2_ctrl, 0);
  662. return 1;
  663. }
  664. int AP_Invensensev2_AuxiliaryBusSlave::read(uint8_t *buf)
  665. {
  666. if (!_registered) {
  667. hal.console->printf("Error: can't read before configuring slave\n");
  668. return -1;
  669. }
  670. auto &backend = AP_InertialSensor_Invensensev2::from(_bus.get_backend());
  671. if (!backend._block_read(INV2REG_EXT_SLV_SENS_DATA_00 + _ext_sens_data, buf, _sample_size)) {
  672. return -1;
  673. }
  674. return _sample_size;
  675. }
  676. /* Invensense provides up to 5 slave devices, but the 5th is way too different to
  677. * configure and is seldom used */
  678. AP_Invensensev2_AuxiliaryBus::AP_Invensensev2_AuxiliaryBus(AP_InertialSensor_Invensensev2 &backend, uint32_t devid)
  679. : AuxiliaryBus(backend, 4, devid)
  680. {
  681. }
  682. AP_HAL::Semaphore *AP_Invensensev2_AuxiliaryBus::get_semaphore()
  683. {
  684. return static_cast<AP_InertialSensor_Invensensev2&>(_ins_backend)._dev->get_semaphore();
  685. }
  686. AuxiliaryBusSlave *AP_Invensensev2_AuxiliaryBus::_instantiate_slave(uint8_t addr, uint8_t instance)
  687. {
  688. /* Enable slaves on Invensense if this is the first time */
  689. if (_ext_sens_data == 0) {
  690. _configure_slaves();
  691. }
  692. return new AP_Invensensev2_AuxiliaryBusSlave(*this, addr, instance);
  693. }
  694. void AP_Invensensev2_AuxiliaryBus::_configure_slaves()
  695. {
  696. auto &backend = AP_InertialSensor_Invensensev2::from(_ins_backend);
  697. if (!backend._dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  698. return;
  699. }
  700. /* Enable the I2C master to slaves on the auxiliary I2C bus*/
  701. if (!(backend._last_stat_user_ctrl & BIT_USER_CTRL_I2C_MST_EN)) {
  702. backend._last_stat_user_ctrl |= BIT_USER_CTRL_I2C_MST_EN;
  703. backend._register_write(INV2REG_USER_CTRL, backend._last_stat_user_ctrl);
  704. }
  705. /* stop condition between reads; clock at 400kHz */
  706. backend._register_write(INV2REG_I2C_MST_CTRL,
  707. BIT_I2C_MST_P_NSR | BIT_I2C_MST_CLK_400KHZ);
  708. /* Hard-code divider for internal sample rate, 1.125 kHz, resulting in a
  709. * sample rate of ~100Hz */
  710. backend._register_write(INV2REG_I2C_SLV4_CTRL, 10);
  711. /* All slaves are subject to the sample rate */
  712. backend._register_write(INV2REG_I2C_MST_DELAY_CTRL,
  713. BIT_I2C_SLV0_DLY_EN | BIT_I2C_SLV1_DLY_EN |
  714. BIT_I2C_SLV2_DLY_EN | BIT_I2C_SLV3_DLY_EN);
  715. backend._dev->get_semaphore()->give();
  716. }
  717. int AP_Invensensev2_AuxiliaryBus::_configure_periodic_read(AuxiliaryBusSlave *slave,
  718. uint8_t reg, uint8_t size)
  719. {
  720. if (_ext_sens_data + size > MAX_EXT_SENS_DATA) {
  721. return -1;
  722. }
  723. AP_Invensensev2_AuxiliaryBusSlave *inv2_slave =
  724. static_cast<AP_Invensensev2_AuxiliaryBusSlave*>(slave);
  725. inv2_slave->_set_passthrough(reg, size);
  726. inv2_slave->_ext_sens_data = _ext_sens_data;
  727. _ext_sens_data += size;
  728. return 0;
  729. }
  730. AP_HAL::Device::PeriodicHandle AP_Invensensev2_AuxiliaryBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  731. {
  732. auto &backend = AP_InertialSensor_Invensensev2::from(_ins_backend);
  733. return backend._dev->register_periodic_callback(period_usec, cb);
  734. }