AP_InertialSensor_RST.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407
  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. IMU driver for Robsense PhenixPro Devkit board including i3g4250d and iis328dq
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ
  18. #include "AP_InertialSensor_RST.h"
  19. #include <AP_Math/AP_Math.h>
  20. #include <inttypes.h>
  21. #include <utility>
  22. #include <math.h>
  23. #include <stdio.h>
  24. const extern AP_HAL::HAL &hal;
  25. #define ADDR_INCREMENT (1<<6)
  26. /************************************iis328dq register addresses *******************************************/
  27. #define ACCEL_WHO_AM_I 0x0F
  28. #define ACCEL_WHO_I_AM 0x32
  29. #define ACCEL_CTRL_REG1 0x20
  30. /* keep lowpass low to avoid noise issues */
  31. #define RATE_50HZ_LP_37HZ (0<<4) | (0<<3)
  32. #define RATE_100HZ_LP_74HZ (0<<4) | (1<<3)
  33. #define RATE_400HZ_LP_292HZ (1<<4) | (0<<3)
  34. #define RATE_1000HZ_LP_780HZ (1<<4) | (1<<3)
  35. #define ACCEL_CTRL_REG2 0x21
  36. #define ACCEL_CTRL_REG3 0x22
  37. #define ACCEL_CTRL_REG4 0x23
  38. #define ACCEL_CTRL_REG5 0x24
  39. #define ACCEL_HP_FILTER_RESETE 0x25
  40. #define ACCEL_OUT_REFERENCE 0x26
  41. #define ACCEL_STATUS_REG 0x27
  42. #define ACCEL_OUT_X_L 0x28
  43. #define ACCEL_OUT_X_H 0x29
  44. #define ACCEL_OUT_Y_L 0x2A
  45. #define ACCEL_OUT_Y_H 0x2B
  46. #define ACCEL_OUT_Z_L 0x2C
  47. #define ACCEL_OUT_Z_H 0x2D
  48. #define ACCEL_INT1_CFG 0x30
  49. #define ACCEL_INT1_SRC 0x31
  50. #define ACCEL_INT1_TSH 0x32
  51. #define ACCEL_INT1_DURATION 0x33
  52. #define ACCEL_INT2_CFG 0x34
  53. #define ACCEL_INT2_SRC 0x35
  54. #define ACCEL_INT2_TSH 0x36
  55. #define ACCEL_INT2_DURATION 0x37
  56. /* Internal configuration values */
  57. #define ACCEL_REG1_POWER_NORMAL ((0<<7) | (0<<6) | (1<<5))
  58. #define ACCEL_REG1_Z_ENABLE (1<<2)
  59. #define ACCEL_REG1_Y_ENABLE (1<<1)
  60. #define ACCEL_REG1_X_ENABLE (1<<0)
  61. #define ACCEL_REG4_BDU (1<<7)
  62. #define ACCEL_REG4_BLE (1<<6)
  63. #define ACCEL_REG4_FULL_SCALE_BITS ((1<<5) | (1<<4))
  64. #define ACCEL_REG4_FULL_SCALE_2G ((0<<5) | (0<<4))
  65. #define ACCEL_REG4_FULL_SCALE_4G ((0<<5) | (1<<4))
  66. #define ACCEL_REG4_FULL_SCALE_8G ((1<<5) | (1<<4))
  67. #define ACCEL_STATUS_ZYXOR (1<<7)
  68. #define ACCEL_STATUS_ZOR (1<<6)
  69. #define ACCEL_STATUS_YOR (1<<5)
  70. #define ACCEL_STATUS_XOR (1<<4)
  71. #define ACCEL_STATUS_ZYXDA (1<<3)
  72. #define ACCEL_STATUS_ZDA (1<<2)
  73. #define ACCEL_STATUS_YDA (1<<1)
  74. #define ACCEL_STATUS_XDA (1<<0)
  75. #define ACCEL_DEFAULT_RANGE_G 8
  76. #define ACCEL_DEFAULT_RATE 1000
  77. #define ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 780
  78. #define ACCEL_ONE_G 9.80665f
  79. /************************************i3g4250d register addresses *******************************************/
  80. #define GYRO_WHO_AM_I 0x0F
  81. #define GYRO_WHO_I_AM 0xD3
  82. #define GYRO_CTRL_REG1 0x20
  83. /* keep lowpass low to avoid noise issues */
  84. #define RATE_100HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
  85. #define RATE_200HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
  86. #define RATE_200HZ_LP_50HZ ((0<<7) | (1<<6) | (1<<5) | (0<<4))
  87. #define RATE_200HZ_LP_70HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
  88. #define RATE_400HZ_LP_20HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
  89. #define RATE_400HZ_LP_25HZ ((1<<7) | (0<<6) | (0<<5) | (1<<4))
  90. #define RATE_400HZ_LP_50HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
  91. #define RATE_400HZ_LP_100HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
  92. #define RATE_800HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4))
  93. #define RATE_800HZ_LP_35HZ ((1<<7) | (1<<6) | (0<<5) | (1<<4))
  94. #define RATE_800HZ_LP_50HZ ((1<<7) | (1<<6) | (1<<5) | (0<<4))
  95. #define RATE_800HZ_LP_100HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
  96. #define GYRO_CTRL_REG2 0x21
  97. #define GYRO_CTRL_REG3 0x22
  98. #define GYRO_CTRL_REG4 0x23
  99. #define RANGE_250DPS (0<<4)
  100. #define RANGE_500DPS (1<<4)
  101. #define RANGE_2000DPS (3<<4)
  102. #define GYRO_CTRL_REG5 0x24
  103. #define GYRO_REFERENCE 0x25
  104. #define GYRO_OUT_TEMP 0x26
  105. #define GYRO_STATUS_REG 0x27
  106. #define GYRO_OUT_X_L 0x28
  107. #define GYRO_OUT_X_H 0x29
  108. #define GYRO_OUT_Y_L 0x2A
  109. #define GYRO_OUT_Y_H 0x2B
  110. #define GYRO_OUT_Z_L 0x2C
  111. #define GYRO_OUT_Z_H 0x2D
  112. #define GYRO_FIFO_CTRL_REG 0x2E
  113. #define GYRO_FIFO_SRC_REG 0x2F
  114. #define GYRO_INT1_CFG 0x30
  115. #define GYRO_INT1_SRC 0x31
  116. #define GYRO_INT1_TSH_XH 0x32
  117. #define GYRO_INT1_TSH_XL 0x33
  118. #define GYRO_INT1_TSH_YH 0x34
  119. #define GYRO_INT1_TSH_YL 0x35
  120. #define GYRO_INT1_TSH_ZH 0x36
  121. #define GYRO_INT1_TSH_ZL 0x37
  122. #define GYRO_INT1_DURATION 0x38
  123. #define GYRO_LOW_ODR 0x39
  124. /* Internal configuration values */
  125. #define GYRO_REG1_POWER_NORMAL (1<<3)
  126. #define GYRO_REG1_Z_ENABLE (1<<2)
  127. #define GYRO_REG1_Y_ENABLE (1<<1)
  128. #define GYRO_REG1_X_ENABLE (1<<0)
  129. #define GYRO_REG4_BLE (1<<6)
  130. #define GYRO_REG5_FIFO_ENABLE (1<<6)
  131. #define GYRO_REG5_REBOOT_MEMORY (1<<7)
  132. #define GYRO_STATUS_ZYXOR (1<<7)
  133. #define GYRO_STATUS_ZOR (1<<6)
  134. #define GYRO_STATUS_YOR (1<<5)
  135. #define GYRO_STATUS_XOR (1<<4)
  136. #define GYRO_STATUS_ZYXDA (1<<3)
  137. #define GYRO_STATUS_ZDA (1<<2)
  138. #define GYRO_STATUS_YDA (1<<1)
  139. #define GYRO_STATUS_XDA (1<<0)
  140. #define GYRO_FIFO_CTRL_BYPASS_MODE (0<<5)
  141. #define GYRO_FIFO_CTRL_FIFO_MODE (1<<5)
  142. #define GYRO_FIFO_CTRL_STREAM_MODE (1<<6)
  143. #define GYRO_FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
  144. #define GYRO_FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
  145. //data output frequency
  146. #define GYRO_DEFAULT_RATE 800
  147. #define GYRO_DEFAULT_RANGE_DPS 2000
  148. #define GYRO_DEFAULT_FILTER_FREQ 35
  149. #define GYRO_TEMP_OFFSET_CELSIUS 40
  150. // constructor
  151. AP_InertialSensor_RST::AP_InertialSensor_RST(AP_InertialSensor &imu,
  152. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
  153. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
  154. enum Rotation rotation_g,
  155. enum Rotation rotation_a)
  156. : AP_InertialSensor_Backend(imu)
  157. , _dev_gyro(std::move(dev_gyro))
  158. , _dev_accel(std::move(dev_accel))
  159. , _rotation_g(rotation_g)
  160. , _rotation_a(rotation_a)
  161. {
  162. }
  163. AP_InertialSensor_RST::~AP_InertialSensor_RST()
  164. {
  165. }
  166. /*
  167. detect the sensor
  168. */
  169. AP_InertialSensor_Backend *AP_InertialSensor_RST::probe(AP_InertialSensor &imu,
  170. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_gyro,
  171. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev_accel,
  172. enum Rotation rotation_g,
  173. enum Rotation rotation_a)
  174. {
  175. if (!dev_gyro && !dev_accel) {
  176. return nullptr;
  177. }
  178. AP_InertialSensor_RST *sensor
  179. = new AP_InertialSensor_RST(imu, std::move(dev_gyro), std::move(dev_accel), rotation_g, rotation_a);
  180. if (!sensor || !sensor->_init_sensor()) {
  181. delete sensor;
  182. return nullptr;
  183. }
  184. return sensor;
  185. }
  186. /*
  187. * init gyro
  188. */
  189. bool AP_InertialSensor_RST::_init_gyro(void)
  190. {
  191. uint8_t whoami;
  192. if (!_dev_gyro->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  193. return false;
  194. }
  195. // set flag for reading registers
  196. _dev_gyro->set_read_flag(0x80);
  197. _dev_gyro->set_speed(AP_HAL::Device::SPEED_HIGH);
  198. _dev_gyro->read_registers(GYRO_WHO_AM_I, &whoami, sizeof(whoami));
  199. if (whoami != GYRO_WHO_I_AM) {
  200. hal.console->printf("RST: unexpected gyro WHOAMI 0x%x\n", (unsigned)whoami);
  201. printf("RST: unexpected gyro WHOAMI 0x%x\n", (unsigned)whoami);
  202. goto fail_whoami;
  203. }
  204. printf("detect i3g4250d\n");
  205. //enter power-down mode first
  206. _dev_gyro->write_register(GYRO_CTRL_REG1, 0);
  207. hal.scheduler->delay(100);
  208. _dev_gyro->write_register(GYRO_CTRL_REG1,
  209. GYRO_REG1_POWER_NORMAL |
  210. GYRO_REG1_Z_ENABLE | GYRO_REG1_X_ENABLE | GYRO_REG1_Y_ENABLE |
  211. RATE_800HZ_LP_50HZ);
  212. /* disable high-pass filters */
  213. _dev_gyro->write_register(GYRO_CTRL_REG2, 0);
  214. /* DRDY disable */
  215. _dev_gyro->write_register(GYRO_CTRL_REG3, 0x0);
  216. _dev_gyro->write_register(GYRO_CTRL_REG4, RANGE_2000DPS);
  217. /* disable wake-on-interrupt */
  218. _dev_gyro->write_register(GYRO_CTRL_REG5, GYRO_REG5_FIFO_ENABLE);
  219. /* disable FIFO. This makes things simpler and ensures we
  220. * aren't getting stale data. It means we must run the hrt
  221. * callback fast enough to not miss data. */
  222. _dev_gyro->write_register(GYRO_FIFO_CTRL_REG, GYRO_FIFO_CTRL_BYPASS_MODE);
  223. _gyro_scale = 70e-3f / 180.0f * M_PI;
  224. hal.scheduler->delay(100);
  225. _dev_gyro->get_semaphore()->give();
  226. return true;
  227. fail_whoami:
  228. _dev_gyro->get_semaphore()->give();
  229. return false;
  230. }
  231. /*
  232. * init accel
  233. */
  234. bool AP_InertialSensor_RST::_init_accel(void)
  235. {
  236. uint8_t whoami;
  237. if (!_dev_accel->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  238. return false;
  239. }
  240. _dev_accel->set_speed(AP_HAL::Device::SPEED_HIGH);
  241. _dev_accel->set_read_flag(0x80);
  242. _dev_accel->read_registers(ACCEL_WHO_AM_I, &whoami, sizeof(whoami));
  243. if (whoami != ACCEL_WHO_I_AM) {
  244. hal.console->printf("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami);
  245. printf("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami);
  246. goto fail_whoami;
  247. }
  248. _dev_accel->write_register(ACCEL_CTRL_REG1,
  249. ACCEL_REG1_POWER_NORMAL |
  250. ACCEL_REG1_Z_ENABLE | ACCEL_REG1_Y_ENABLE | ACCEL_REG1_X_ENABLE |
  251. RATE_1000HZ_LP_780HZ);
  252. /* disable high-pass filters */
  253. _dev_accel->write_register(ACCEL_CTRL_REG2, 0);
  254. /* DRDY enable */
  255. _dev_accel->write_register(ACCEL_CTRL_REG3, 0x02);
  256. _dev_accel->write_register(ACCEL_CTRL_REG4,
  257. ACCEL_REG4_BDU | ACCEL_REG4_FULL_SCALE_8G);
  258. _accel_scale = 0.244e-3f * ACCEL_ONE_G;
  259. _dev_accel->get_semaphore()->give();
  260. return true;
  261. fail_whoami:
  262. _dev_accel->get_semaphore()->give();
  263. return false;
  264. }
  265. bool AP_InertialSensor_RST::_init_sensor(void)
  266. {
  267. if (!_init_gyro() || !_init_accel()) {
  268. return false;
  269. }
  270. return true;
  271. }
  272. /*
  273. startup the sensor
  274. */
  275. void AP_InertialSensor_RST::start(void)
  276. {
  277. _gyro_instance = _imu.register_gyro(800, _dev_gyro->get_bus_id_devtype(DEVTYPE_GYR_I3G4250D));
  278. _accel_instance = _imu.register_accel(1000, _dev_accel->get_bus_id_devtype(DEVTYPE_ACC_IIS328DQ));
  279. set_gyro_orientation(_gyro_instance, _rotation_g);
  280. set_accel_orientation(_accel_instance, _rotation_a);
  281. // start the timer process to read samples
  282. _dev_gyro->register_periodic_callback(1150, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_RST::gyro_measure, void));
  283. _dev_accel->register_periodic_callback(800, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_RST::accel_measure, void));
  284. }
  285. /*
  286. copy filtered data to the frontend
  287. */
  288. bool AP_InertialSensor_RST::update(void)
  289. {
  290. update_gyro(_gyro_instance);
  291. update_accel(_accel_instance);
  292. return true;
  293. }
  294. // Accumulate values from gyros
  295. void AP_InertialSensor_RST::gyro_measure(void)
  296. {
  297. Vector3f gyro;
  298. uint8_t status = 0;
  299. int16_t raw_data[3];
  300. _dev_gyro->read_registers(GYRO_STATUS_REG, &status, sizeof(status));
  301. if ((status & GYRO_STATUS_ZYXDA) == 0) {
  302. return;
  303. }
  304. if (_dev_gyro->read_registers(GYRO_OUT_X_L | ADDR_INCREMENT, (uint8_t *)raw_data, sizeof(raw_data))) {
  305. gyro = Vector3f(raw_data[0], raw_data[1], raw_data[2]);
  306. gyro *= _gyro_scale;
  307. _rotate_and_correct_gyro(_gyro_instance, gyro);
  308. _notify_new_gyro_raw_sample(_gyro_instance, gyro);
  309. }
  310. }
  311. // Accumulate values from accels
  312. void AP_InertialSensor_RST::accel_measure(void)
  313. {
  314. Vector3f accel;
  315. uint8_t status = 0;
  316. int16_t raw_data[3];
  317. _dev_accel->read_registers(ACCEL_STATUS_REG, &status, sizeof(status));
  318. if ((status & ACCEL_STATUS_ZYXDA) == 0) {
  319. return;
  320. }
  321. if (_dev_accel->read_registers(ACCEL_OUT_X_L | ADDR_INCREMENT, (uint8_t *)raw_data, sizeof(raw_data))) {
  322. accel = Vector3f(raw_data[0], raw_data[1], raw_data[2]);
  323. accel *= _accel_scale;
  324. _rotate_and_correct_accel(_accel_instance, accel);
  325. _notify_new_accel_raw_sample(_accel_instance, accel);
  326. }
  327. }
  328. #endif