AP_InertialSensor_LSM9DS0.cpp 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799
  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. #include <AP_HAL/AP_HAL.h>
  16. #include "AP_InertialSensor_LSM9DS0.h"
  17. #include <utility>
  18. extern const AP_HAL::HAL &hal;
  19. #define LSM9DS0_DRY_X_PIN -1
  20. #define LSM9DS0_DRY_G_PIN -1
  21. #define LSM9DS0_G_WHOAMI 0xD4 // L3GD20
  22. #define LSM9DS0_G_WHOAMI_H 0xD7 // L3GD20H
  23. #define LSM9DS0_XM_WHOAMI 0x49
  24. ////////////////////////////
  25. // LSM9DS0 Gyro Registers //
  26. ////////////////////////////
  27. #define WHO_AM_I_G 0x0F
  28. #define CTRL_REG1_G 0x20
  29. # define CTRL_REG1_G_DR_95Hz_BW_12500mHz (0x0 << 4)
  30. # define CTRL_REG1_G_DR_95Hz_BW_25Hz (0x1 << 4)
  31. # define CTRL_REG1_G_DR_190Hz_BW_12500mHz (0x4 << 4)
  32. # define CTRL_REG1_G_DR_190Hz_BW_25Hz (0x5 << 4)
  33. # define CTRL_REG1_G_DR_190Hz_BW_50Hz (0x6 << 4)
  34. # define CTRL_REG1_G_DR_190Hz_BW_70Hz (0x7 << 4)
  35. # define CTRL_REG1_G_DR_380Hz_BW_20Hz (0x8 << 4)
  36. # define CTRL_REG1_G_DR_380Hz_BW_25Hz (0x9 << 4)
  37. # define CTRL_REG1_G_DR_380Hz_BW_50Hz (0xA << 4)
  38. # define CTRL_REG1_G_DR_380Hz_BW_100Hz (0xB << 4)
  39. # define CTRL_REG1_G_DR_760Hz_BW_30Hz (0xC << 4)
  40. # define CTRL_REG1_G_DR_760Hz_BW_35Hz (0xD << 4)
  41. # define CTRL_REG1_G_DR_760Hz_BW_50Hz (0xE << 4)
  42. # define CTRL_REG1_G_DR_760Hz_BW_100Hz (0xF << 4)
  43. # define CTRL_REG1_G_PD (0x1 << 3)
  44. # define CTRL_REG1_G_ZEN (0x1 << 2)
  45. # define CTRL_REG1_G_YEN (0x1 << 1)
  46. # define CTRL_REG1_G_XEN (0x1 << 0)
  47. #define CTRL_REG2_G 0x21
  48. # define CTRL_REG2_G_HPM_NORMAL_RESET (0x0 << 4)
  49. # define CTRL_REG2_G_HPM_REFERENCE (0x1 << 4)
  50. # define CTRL_REG2_G_HPM_NORMAL (0x2 << 4)
  51. # define CTRL_REG2_G_HPM_AUTORESET (0x3 << 4)
  52. # define CTRL_REG2_G_HPCF_0 (0x0 << 0)
  53. # define CTRL_REG2_G_HPCF_1 (0x1 << 0)
  54. # define CTRL_REG2_G_HPCF_2 (0x2 << 0)
  55. # define CTRL_REG2_G_HPCF_3 (0x3 << 0)
  56. # define CTRL_REG2_G_HPCF_4 (0x4 << 0)
  57. # define CTRL_REG2_G_HPCF_5 (0x5 << 0)
  58. # define CTRL_REG2_G_HPCF_6 (0x6 << 0)
  59. # define CTRL_REG2_G_HPCF_7 (0x7 << 0)
  60. # define CTRL_REG2_G_HPCF_8 (0x8 << 0)
  61. # define CTRL_REG2_G_HPCF_9 (0x9 << 0)
  62. #define CTRL_REG3_G 0x22
  63. # define CTRL_REG3_G_I1_INT1 (0x1 << 7)
  64. # define CTRL_REG3_G_I1_BOOT (0x1 << 6)
  65. # define CTRL_REG3_G_H_LACTIVE (0x1 << 5)
  66. # define CTRL_REG3_G_PP_OD (0x1 << 4)
  67. # define CTRL_REG3_G_I2_DRDY (0x1 << 3)
  68. # define CTRL_REG3_G_I2_WTM (0x1 << 2)
  69. # define CTRL_REG3_G_I2_ORUN (0x1 << 1)
  70. # define CTRL_REG3_G_I2_EMPTY (0x1 << 0)
  71. #define CTRL_REG4_G 0x23
  72. # define CTRL_REG4_G_BDU (0x1 << 7)
  73. # define CTRL_REG4_G_BLE (0x1 << 6)
  74. # define CTRL_REG4_G_FS_245DPS (0x0 << 4)
  75. # define CTRL_REG4_G_FS_500DPS (0x1 << 4)
  76. # define CTRL_REG4_G_FS_2000DPS (0x2 << 4)
  77. # define CTRL_REG4_G_ST_NORMAL (0x0 << 1)
  78. # define CTRL_REG4_G_ST_0 (0x1 << 1)
  79. # define CTRL_REG4_G_ST_1 (0x3 << 1)
  80. # define CTRL_REG4_G_SIM_3WIRE (0x1 << 0)
  81. #define CTRL_REG5_G 0x24
  82. # define CTRL_REG5_G_BOOT (0x1 << 7)
  83. # define CTRL_REG5_G_FIFO_EN (0x1 << 6)
  84. # define CTRL_REG5_G_HPEN (0x1 << 4)
  85. # define CTRL_REG5_G_INT1_SEL_00 (0x0 << 2)
  86. # define CTRL_REG5_G_INT1_SEL_01 (0x1 << 2)
  87. # define CTRL_REG5_G_INT1_SEL_10 (0x2 << 2)
  88. # define CTRL_REG5_G_INT1_SEL_11 (0x3 << 2)
  89. # define CTRL_REG5_G_OUT_SEL_00 (0x0 << 0)
  90. # define CTRL_REG5_G_OUT_SEL_01 (0x1 << 0)
  91. # define CTRL_REG5_G_OUT_SEL_10 (0x2 << 0)
  92. # define CTRL_REG5_G_OUT_SEL_11 (0x3 << 0)
  93. #define REFERENCE_G 0x25
  94. #define STATUS_REG_G 0x27
  95. # define STATUS_REG_G_ZYXOR (0x1 << 7)
  96. # define STATUS_REG_G_ZOR (0x1 << 6)
  97. # define STATUS_REG_G_YOR (0x1 << 5)
  98. # define STATUS_REG_G_XOR (0x1 << 4)
  99. # define STATUS_REG_G_ZYXDA (0x1 << 3)
  100. # define STATUS_REG_G_ZDA (0x1 << 2)
  101. # define STATUS_REG_G_YDA (0x1 << 1)
  102. # define STATUS_REG_G_XDA (0x1 << 0)
  103. #define OUT_X_L_G 0x28
  104. #define OUT_X_H_G 0x29
  105. #define OUT_Y_L_G 0x2A
  106. #define OUT_Y_H_G 0x2B
  107. #define OUT_Z_L_G 0x2C
  108. #define OUT_Z_H_G 0x2D
  109. #define FIFO_CTRL_REG_G 0x2E
  110. # define FIFO_CTRL_REG_G_FM_BYPASS (0x0 << 5)
  111. # define FIFO_CTRL_REG_G_FM_FIFO (0x1 << 5)
  112. # define FIFO_CTRL_REG_G_FM_STREAM (0x2 << 5)
  113. # define FIFO_CTRL_REG_G_FM_STREAM_TO_FIFO (0x3 << 5)
  114. # define FIFO_CTRL_REG_G_FM_BYPASS_TO_STREAM (0x4 << 5)
  115. # define FIFO_CTRL_REG_G_WTM_MASK 0x1F
  116. #define FIFO_SRC_REG_G 0x2F
  117. # define FIFO_SRC_REG_G_WTM (0x1 << 7)
  118. # define FIFO_SRC_REG_G_OVRN (0x1 << 6)
  119. # define FIFO_SRC_REG_G_EMPTY (0x1 << 5)
  120. # define FIFO_SRC_REG_G_FSS_MASK 0x1F
  121. #define INT1_CFG_G 0x30
  122. # define INT1_CFG_G_AND_OR (0x1 << 7)
  123. # define INT1_CFG_G_LIR (0x1 << 6)
  124. # define INT1_CFG_G_ZHIE (0x1 << 5)
  125. # define INT1_CFG_G_ZLIE (0x1 << 4)
  126. # define INT1_CFG_G_YHIE (0x1 << 3)
  127. # define INT1_CFG_G_YLIE (0x1 << 2)
  128. # define INT1_CFG_G_XHIE (0x1 << 1)
  129. # define INT1_CFG_G_XLIE (0x1 << 0)
  130. #define INT1_SRC_G 0x31
  131. # define INT1_SRC_G_IA (0x1 << 6)
  132. # define INT1_SRC_G_ZH (0x1 << 5)
  133. # define INT1_SRC_G_ZL (0x1 << 4)
  134. # define INT1_SRC_G_YH (0x1 << 3)
  135. # define INT1_SRC_G_YL (0x1 << 2)
  136. # define INT1_SRC_G_XH (0x1 << 1)
  137. # define INT1_SRC_G_XL (0x1 << 0)
  138. #define INT1_THS_XH_G 0x32
  139. #define INT1_THS_XL_G 0x33
  140. #define INT1_THS_YH_G 0x34
  141. #define INT1_THS_YL_G 0x35
  142. #define INT1_THS_ZH_G 0x36
  143. #define INT1_THS_ZL_G 0x37
  144. #define INT1_DURATION_G 0x38
  145. # define INT1_DURATION_G_WAIT (0x1 << 7)
  146. # define INT1_DURATION_G_D_MASK 0x7F
  147. //////////////////////////////////////////
  148. // LSM9DS0 Accel/Magneto (XM) Registers //
  149. //////////////////////////////////////////
  150. #define OUT_TEMP_L_XM 0x05
  151. #define OUT_TEMP_H_XM 0x06
  152. #define STATUS_REG_M 0x07
  153. # define STATUS_REG_M_ZYXMOR (0x1 << 7)
  154. # define STATUS_REG_M_ZMOR (0x1 << 6)
  155. # define STATUS_REG_M_YMOR (0x1 << 5)
  156. # define STATUS_REG_M_XMOR (0x1 << 4)
  157. # define STATUS_REG_M_ZYXMDA (0x1 << 3)
  158. # define STATUS_REG_M_ZMDA (0x1 << 2)
  159. # define STATUS_REG_M_YMDA (0x1 << 1)
  160. # define STATUS_REG_M_XMDA (0x1 << 0)
  161. #define OUT_X_L_M 0x08
  162. #define OUT_X_H_M 0x09
  163. #define OUT_Y_L_M 0x0A
  164. #define OUT_Y_H_M 0x0B
  165. #define OUT_Z_L_M 0x0C
  166. #define OUT_Z_H_M 0x0D
  167. #define WHO_AM_I_XM 0x0F
  168. #define INT_CTRL_REG_M 0x12
  169. # define INT_CTRL_REG_M_XMIEN (0x1 << 7)
  170. # define INT_CTRL_REG_M_YMIEN (0x1 << 6)
  171. # define INT_CTRL_REG_M_ZMIEN (0x1 << 5)
  172. # define INT_CTRL_REG_M_PP_OD (0x1 << 4)
  173. # define INT_CTRL_REG_M_IEA (0x1 << 3)
  174. # define INT_CTRL_REG_M_IEL (0x1 << 2)
  175. # define INT_CTRL_REG_M_4D (0x1 << 1)
  176. # define INT_CTRL_REG_M_MIEN (0x1 << 0)
  177. #define INT_SRC_REG_M 0x13
  178. # define INT_SRC_REG_M_M_PTH_X (0x1 << 7)
  179. # define INT_SRC_REG_M_M_PTH_Y (0x1 << 6)
  180. # define INT_SRC_REG_M_M_PTH_Z (0x1 << 5)
  181. # define INT_SRC_REG_M_M_NTH_X (0x1 << 4)
  182. # define INT_SRC_REG_M_M_NTH_Y (0x1 << 3)
  183. # define INT_SRC_REG_M_M_NTH_Z (0x1 << 2)
  184. # define INT_SRC_REG_M_MROI (0x1 << 1)
  185. # define INT_SRC_REG_M_MINT (0x1 << 0)
  186. #define INT_THS_L_M 0x14
  187. #define INT_THS_H_M 0x15
  188. #define OFFSET_X_L_M 0x16
  189. #define OFFSET_X_H_M 0x17
  190. #define OFFSET_Y_L_M 0x18
  191. #define OFFSET_Y_H_M 0x19
  192. #define OFFSET_Z_L_M 0x1A
  193. #define OFFSET_Z_H_M 0x1B
  194. #define REFERENCE_X 0x1C
  195. #define REFERENCE_Y 0x1D
  196. #define REFERENCE_Z 0x1E
  197. #define CTRL_REG0_XM 0x1F
  198. # define CTRL_REG0_XM_B00T (0x1 << 7)
  199. # define CTRL_REG0_XM_FIFO_EN (0x1 << 6)
  200. # define CTRL_REG0_XM_WTM_EN (0x1 << 5)
  201. # define CTRL_REG0_XM_HP_CLICK (0x1 << 2)
  202. # define CTRL_REG0_XM_HPIS1 (0x1 << 1)
  203. # define CTRL_REG0_XM_HPIS2 (0x1 << 0)
  204. #define CTRL_REG1_XM 0x20
  205. # define CTRL_REG1_XM_AODR_POWERDOWN (0x0 << 4)
  206. # define CTRL_REG1_XM_AODR_3125mHz (0x1 << 4)
  207. # define CTRL_REG1_XM_AODR_6250mHz (0x2 << 4)
  208. # define CTRL_REG1_XM_AODR_12500mHz (0x3 << 4)
  209. # define CTRL_REG1_XM_AODR_25Hz (0x4 << 4)
  210. # define CTRL_REG1_XM_AODR_50Hz (0x5 << 4)
  211. # define CTRL_REG1_XM_AODR_100Hz (0x6 << 4)
  212. # define CTRL_REG1_XM_AODR_200Hz (0x7 << 4)
  213. # define CTRL_REG1_XM_AODR_400Hz (0x8 << 4)
  214. # define CTRL_REG1_XM_AODR_800Hz (0x9 << 4)
  215. # define CTRL_REG1_XM_AODR_1600Hz (0xA << 4)
  216. # define CTRL_REG1_XM_BDU (0x1 << 3)
  217. # define CTRL_REG1_XM_AZEN (0x1 << 2)
  218. # define CTRL_REG1_XM_AYEN (0x1 << 1)
  219. # define CTRL_REG1_XM_AXEN (0x1 << 0)
  220. #define CTRL_REG2_XM 0x21
  221. # define CTRL_REG2_XM_ABW_773Hz (0x0 << 6)
  222. # define CTRL_REG2_XM_ABW_194Hz (0x1 << 6)
  223. # define CTRL_REG2_XM_ABW_362Hz (0x2 << 6)
  224. # define CTRL_REG2_XM_ABW_50Hz (0x3 << 6)
  225. # define CTRL_REG2_XM_AFS_2G (0x0 << 3)
  226. # define CTRL_REG2_XM_AFS_4G (0x1 << 3)
  227. # define CTRL_REG2_XM_AFS_6G (0x2 << 3)
  228. # define CTRL_REG2_XM_AFS_8G (0x3 << 3)
  229. # define CTRL_REG2_XM_AFS_16G (0x4 << 3)
  230. # define CTRL_REG2_XM_AST_NORMAL (0x0 << 1)
  231. # define CTRL_REG2_XM_AST_POSITIVE (0x1 << 1)
  232. # define CTRL_REG2_XM_AST_NEGATIVE (0x2 << 1)
  233. # define CTRL_REG2_XM_SIM_3WIRE (0x1 << 0)
  234. #define CTRL_REG3_XM 0x22
  235. # define CTRL_REG3_XM_P1_BOOT (0x1 << 7)
  236. # define CTRL_REG3_XM_P1_TAP (0x1 << 6)
  237. # define CTRL_REG3_XM_P1_INT1 (0x1 << 5)
  238. # define CTRL_REG3_XM_P1_INT2 (0x1 << 4)
  239. # define CTRL_REG3_XM_P1_INTM (0x1 << 3)
  240. # define CTRL_REG3_XM_P1_DRDYA (0x1 << 2)
  241. # define CTRL_REG3_XM_P1_DRDYM (0x1 << 1)
  242. # define CTRL_REG3_XM_P1_EMPTY (0x1 << 0)
  243. #define CTRL_REG4_XM 0x23
  244. # define CTRL_REG4_XM_P2_TAP (0x1 << 7)
  245. # define CTRL_REG4_XM_P2_INT1 (0x1 << 6)
  246. # define CTRL_REG4_XM_P2_INT2 (0x1 << 5)
  247. # define CTRL_REG4_XM_P2_INTM (0x1 << 4)
  248. # define CTRL_REG4_XM_P2_DRDYA (0x1 << 3)
  249. # define CTRL_REG4_XM_P2_DRDYM (0x1 << 2)
  250. # define CTRL_REG4_XM_P2_OVERRUN (0x1 << 1)
  251. # define CTRL_REG4_XM_P2_WTM (0x1 << 0)
  252. #define CTRL_REG5_XM 0x24
  253. # define CTRL_REG5_XM_TEMP_EN (0x1 << 7)
  254. # define CTRL_REG5_XM_M_RES_LOW (0x0 << 5)
  255. # define CTRL_REG5_XM_M_RES_HIGH (0x3 << 5)
  256. # define CTRL_REG5_XM_ODR_3125mHz (0x0 << 2)
  257. # define CTRL_REG5_XM_ODR_6250mHz (0x1 << 2)
  258. # define CTRL_REG5_XM_ODR_12500mHz (0x2 << 2)
  259. # define CTRL_REG5_XM_ODR_25Hz (0x3 << 2)
  260. # define CTRL_REG5_XM_ODR_50Hz (0x4 << 2)
  261. # define CTRL_REG5_XM_ODR_100Hz (0x5 << 2)
  262. # define CTRL_REG5_XM_LIR2 (0x1 << 1)
  263. # define CTRL_REG5_XM_LIR1 (0x1 << 0)
  264. #define CTRL_REG6_XM 0x25
  265. # define CTRL_REG6_XM_MFS_2Gs (0x0 << 5)
  266. # define CTRL_REG6_XM_MFS_4Gs (0x1 << 5)
  267. # define CTRL_REG6_XM_MFS_8Gs (0x2 << 5)
  268. # define CTRL_REG6_XM_MFS_12Gs (0x3 << 5)
  269. #define CTRL_REG7_XM 0x26
  270. # define CTRL_REG7_XM_AHPM_NORMAL_RESET (0x0 << 6)
  271. # define CTRL_REG7_XM_AHPM_REFERENCE (0x1 << 6)
  272. # define CTRL_REG7_XM_AHPM_NORMAL (0x2 << 6)
  273. # define CTRL_REG7_XM_AHPM_AUTORESET (0x3 << 6)
  274. # define CTRL_REG7_XM_AFDS (0x1 << 5)
  275. # define CTRL_REG7_XM_MLP (0x1 << 2)
  276. # define CTRL_REG7_XM_MD_CONTINUOUS (0x0 << 0)
  277. # define CTRL_REG7_XM_MD_SINGLE (0x1 << 0)
  278. # define CTRL_REG7_XM_MD_POWERDOWN (0x2 << 0)
  279. #define STATUS_REG_A 0x27
  280. # define STATUS_REG_A_ZYXAOR (0x1 << 7)
  281. # define STATUS_REG_A_ZAOR (0x1 << 6)
  282. # define STATUS_REG_A_YAOR (0x1 << 5)
  283. # define STATUS_REG_A_XAOR (0x1 << 4)
  284. # define STATUS_REG_A_ZYXADA (0x1 << 3)
  285. # define STATUS_REG_A_ZADA (0x1 << 2)
  286. # define STATUS_REG_A_YADA (0x1 << 1)
  287. # define STATUS_REG_A_XADA (0x1 << 0)
  288. #define OUT_X_L_A 0x28
  289. #define OUT_X_H_A 0x29
  290. #define OUT_Y_L_A 0x2A
  291. #define OUT_Y_H_A 0x2B
  292. #define OUT_Z_L_A 0x2C
  293. #define OUT_Z_H_A 0x2D
  294. #define FIFO_CTRL_REG 0x2E
  295. # define FIFO_CTRL_REG_FM_BYPASS (0x0 << 5)
  296. # define FIFO_CTRL_REG_FM_FIFO (0x1 << 5)
  297. # define FIFO_CTRL_REG_FM_STREAM (0x2 << 5)
  298. # define FIFO_CTRL_REG_FM_STREAM_TO_FIFO (0x3 << 5)
  299. # define FIFO_CTRL_REG_FM_BYPASS_TO_STREAM (0x4 << 5)
  300. # define FIFO_CTRL_REG_FTH_MASK 0x1F
  301. #define FIFO_SRC_REG 0x2F
  302. # define FIFO_SRC_REG_WTM (0x1 << 7)
  303. # define FIFO_SRC_REG_OVRN (0x1 << 6)
  304. # define FIFO_SRC_REG_EMPTY (0x1 << 5)
  305. # define FIFO_SRC_REG_FSS_MASK 0x1F
  306. #define INT_GEN_1_REG 0x30
  307. # define INT_GEN_1_REG_AOI (0x1 << 7)
  308. # define INT_GEN_1_REG_6D (0x1 << 6)
  309. # define INT_GEN_1_REG_ZHIE_ZUPE (0x1 << 5)
  310. # define INT_GEN_1_REG_ZLIE_ZDOWNE (0x1 << 4)
  311. # define INT_GEN_1_REG_YHIE_YUPE (0x1 << 3)
  312. # define INT_GEN_1_REG_YLIE_YDOWNE (0x1 << 2)
  313. # define INT_GEN_1_REG_XHIE_XUPE (0x1 << 1)
  314. # define INT_GEN_1_REG_XLIE_XDOWNE (0x1 << 0)
  315. #define INT_GEN_1_SRC 0x31
  316. # define INT_GEN_1_SRC_IA (0x1 << 6)
  317. # define INT_GEN_1_SRC_ZH (0x1 << 5)
  318. # define INT_GEN_1_SRC_ZL (0x1 << 4)
  319. # define INT_GEN_1_SRC_YH (0x1 << 3)
  320. # define INT_GEN_1_SRC_YL (0x1 << 2)
  321. # define INT_GEN_1_SRC_XH (0x1 << 1)
  322. # define INT_GEN_1_SRC_XL (0x1 << 0)
  323. #define INT_GEN_1_THS 0x32
  324. #define INT_GEN_1_DURATION 0x33
  325. #define INT_GEN_2_REG 0x34
  326. # define INT_GEN_2_REG_AOI (0x1 << 7)
  327. # define INT_GEN_2_REG_6D (0x1 << 6)
  328. # define INT_GEN_2_REG_ZHIE_ZUPE (0x1 << 5)
  329. # define INT_GEN_2_REG_ZLIE_ZDOWNE (0x1 << 4)
  330. # define INT_GEN_2_REG_YHIE_YUPE (0x1 << 3)
  331. # define INT_GEN_2_REG_YLIE_YDOWNE (0x1 << 2)
  332. # define INT_GEN_2_REG_XHIE_XUPE (0x1 << 1)
  333. # define INT_GEN_2_REG_XLIE_XDOWNE (0x1 << 0)
  334. #define INT_GEN_2_SRC 0x35
  335. # define INT_GEN_2_SRC_IA (0x1 << 6)
  336. # define INT_GEN_2_SRC_ZH (0x1 << 5)
  337. # define INT_GEN_2_SRC_ZL (0x1 << 4)
  338. # define INT_GEN_2_SRC_YH (0x1 << 3)
  339. # define INT_GEN_2_SRC_YL (0x1 << 2)
  340. # define INT_GEN_2_SRC_XH (0x1 << 1)
  341. # define INT_GEN_2_SRC_XL (0x1 << 0)
  342. #define INT_GEN_2_THS 0x36
  343. #define INT_GEN_2_DURATION 0x37
  344. #define CLICK_CFG 0x38
  345. # define CLICK_CFG_ZD (0x1 << 5)
  346. # define CLICK_CFG_ZS (0x1 << 4)
  347. # define CLICK_CFG_YD (0x1 << 3)
  348. # define CLICK_CFG_YS (0x1 << 2)
  349. # define CLICK_CFG_XD (0x1 << 1)
  350. # define CLICK_CFG_XS (0x1 << 0)
  351. #define CLICK_SRC 0x39
  352. # define CLICK_SRC_IA (0x1 << 6)
  353. # define CLICK_SRC_DCLICK (0x1 << 5)
  354. # define CLICK_SRC_SCLICK (0x1 << 4)
  355. # define CLICK_SRC_SIGN (0x1 << 3)
  356. # define CLICK_SRC_Z (0x1 << 2)
  357. # define CLICK_SRC_Y (0x1 << 1)
  358. # define CLICK_SRC_X (0x1 << 0)
  359. #define CLICK_THS 0x3A
  360. #define TIME_LIMIT 0x3B
  361. #define TIME_LATENCY 0x3C
  362. #define TIME_WINDOW 0x3D
  363. #define ACT_THS 0x3E
  364. #define ACT_DUR 0x3F
  365. AP_InertialSensor_LSM9DS0::AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu,
  366. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro,
  367. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel,
  368. int drdy_pin_num_a,
  369. int drdy_pin_num_g,
  370. enum Rotation rotation_a,
  371. enum Rotation rotation_g,
  372. enum Rotation rotation_gH)
  373. : AP_InertialSensor_Backend(imu)
  374. , _dev_gyro(std::move(dev_gyro))
  375. , _dev_accel(std::move(dev_accel))
  376. , _drdy_pin_num_a(drdy_pin_num_a)
  377. , _drdy_pin_num_g(drdy_pin_num_g)
  378. , _rotation_a(rotation_a)
  379. , _rotation_g(rotation_g)
  380. , _rotation_gH(rotation_gH)
  381. {
  382. }
  383. AP_InertialSensor_Backend *AP_InertialSensor_LSM9DS0::probe(AP_InertialSensor &_imu,
  384. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro,
  385. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel,
  386. enum Rotation rotation_a,
  387. enum Rotation rotation_g,
  388. enum Rotation rotation_gH)
  389. {
  390. if (!dev_gyro || !dev_accel) {
  391. return nullptr;
  392. }
  393. AP_InertialSensor_LSM9DS0 *sensor =
  394. new AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel),
  395. LSM9DS0_DRY_X_PIN, LSM9DS0_DRY_G_PIN,
  396. rotation_a, rotation_g, rotation_gH);
  397. if (!sensor || !sensor->_init_sensor()) {
  398. delete sensor;
  399. return nullptr;
  400. }
  401. return sensor;
  402. }
  403. bool AP_InertialSensor_LSM9DS0::_init_sensor()
  404. {
  405. /*
  406. * Same semaphore for both since they necessarily share the same bus (with
  407. * different CS)
  408. */
  409. _spi_sem = _dev_gyro->get_semaphore();
  410. if (_drdy_pin_num_a >= 0) {
  411. _drdy_pin_a = hal.gpio->channel(_drdy_pin_num_a);
  412. if (_drdy_pin_a == nullptr) {
  413. AP_HAL::panic("LSM9DS0: null accel data-ready GPIO channel\n");
  414. }
  415. _drdy_pin_a->mode(HAL_GPIO_INPUT);
  416. }
  417. if (_drdy_pin_num_g >= 0) {
  418. _drdy_pin_g = hal.gpio->channel(_drdy_pin_num_g);
  419. if (_drdy_pin_g == nullptr) {
  420. AP_HAL::panic("LSM9DS0: null gyro data-ready GPIO channel\n");
  421. }
  422. _drdy_pin_g->mode(HAL_GPIO_INPUT);
  423. }
  424. bool success = _hardware_init();
  425. #if LSM9DS0_DEBUG
  426. _dump_registers();
  427. #endif
  428. return success;
  429. }
  430. bool AP_InertialSensor_LSM9DS0::_hardware_init()
  431. {
  432. if (!_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  433. return false;
  434. }
  435. uint8_t tries, whoami;
  436. // set flag for reading registers
  437. _dev_gyro->set_read_flag(0x80);
  438. _dev_accel->set_read_flag(0x80);
  439. whoami_g = _register_read_g(WHO_AM_I_G);
  440. if (whoami_g != LSM9DS0_G_WHOAMI && whoami_g != LSM9DS0_G_WHOAMI_H) {
  441. goto fail_whoami;
  442. }
  443. whoami = _register_read_xm(WHO_AM_I_XM);
  444. if (whoami != LSM9DS0_XM_WHOAMI) {
  445. goto fail_whoami;
  446. }
  447. // setup for register checking
  448. _dev_gyro->setup_checked_registers(5, 20);
  449. _dev_accel->setup_checked_registers(4, 20);
  450. for (tries = 0; tries < 5; tries++) {
  451. _dev_gyro->set_speed(AP_HAL::Device::SPEED_LOW);
  452. _dev_accel->set_speed(AP_HAL::Device::SPEED_LOW);
  453. _gyro_init();
  454. _accel_init();
  455. _dev_gyro->set_speed(AP_HAL::Device::SPEED_HIGH);
  456. _dev_accel->set_speed(AP_HAL::Device::SPEED_HIGH);
  457. hal.scheduler->delay(10);
  458. if (_accel_data_ready() && _gyro_data_ready()) {
  459. break;
  460. }
  461. #if LSM9DS0_DEBUG
  462. _dump_registers();
  463. #endif
  464. }
  465. if (tries == 5) {
  466. hal.console->printf("Failed to boot LSM9DS0 5 times\n\n");
  467. goto fail_tries;
  468. }
  469. _spi_sem->give();
  470. return true;
  471. fail_tries:
  472. fail_whoami:
  473. _spi_sem->give();
  474. return false;
  475. }
  476. /*
  477. start the sensor going
  478. */
  479. void AP_InertialSensor_LSM9DS0::start(void)
  480. {
  481. _gyro_instance = _imu.register_gyro(760, _dev_gyro->get_bus_id_devtype(DEVTYPE_GYR_L3GD20));
  482. _accel_instance = _imu.register_accel(1000, _dev_accel->get_bus_id_devtype(DEVTYPE_ACC_LSM303D));
  483. if (whoami_g == LSM9DS0_G_WHOAMI_H) {
  484. set_gyro_orientation(_gyro_instance, _rotation_gH);
  485. } else {
  486. set_gyro_orientation(_gyro_instance, _rotation_g);
  487. }
  488. set_accel_orientation(_accel_instance, _rotation_a);
  489. _set_accel_max_abs_offset(_accel_instance, 5.0f);
  490. /* start the timer process to read samples */
  491. _dev_gyro->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_LSM9DS0::_poll_data, void));
  492. }
  493. uint8_t AP_InertialSensor_LSM9DS0::_register_read_xm(uint8_t reg)
  494. {
  495. uint8_t val = 0;
  496. _dev_accel->read_registers(reg, &val, 1);
  497. return val;
  498. }
  499. uint8_t AP_InertialSensor_LSM9DS0::_register_read_g(uint8_t reg)
  500. {
  501. uint8_t val = 0;
  502. _dev_gyro->read_registers(reg, &val, 1);
  503. return val;
  504. }
  505. void AP_InertialSensor_LSM9DS0::_register_write_xm(uint8_t reg, uint8_t val, bool checked)
  506. {
  507. _dev_accel->write_register(reg, val, checked);
  508. }
  509. void AP_InertialSensor_LSM9DS0::_register_write_g(uint8_t reg, uint8_t val, bool checked)
  510. {
  511. _dev_gyro->write_register(reg, val, checked);
  512. }
  513. void AP_InertialSensor_LSM9DS0::_gyro_disable_i2c()
  514. {
  515. uint8_t retries = 10;
  516. while (retries--) {
  517. // add retries
  518. uint8_t a = _register_read_g(0x05);
  519. _register_write_g(0x05, (0x20 | a));
  520. if (_register_read_g(0x05) == (a | 0x20)) {
  521. return;
  522. }
  523. }
  524. AP_HAL::panic("LSM9DS0_G: Unable to disable I2C");
  525. }
  526. void AP_InertialSensor_LSM9DS0::_accel_disable_i2c()
  527. {
  528. uint8_t a = _register_read_xm(0x02);
  529. _register_write_xm(0x02, (0x10 | a));
  530. a = _register_read_xm(0x02);
  531. _register_write_xm(0x02, (0xF7 & a));
  532. a = _register_read_xm(0x15);
  533. _register_write_xm(0x15, (0x80 | a));
  534. a = _register_read_xm(0x02);
  535. _register_write_xm(0x02, (0xE7 & a));
  536. }
  537. void AP_InertialSensor_LSM9DS0::_gyro_init()
  538. {
  539. _gyro_disable_i2c();
  540. hal.scheduler->delay(1);
  541. _register_write_g(CTRL_REG1_G,
  542. CTRL_REG1_G_DR_760Hz_BW_50Hz |
  543. CTRL_REG1_G_PD |
  544. CTRL_REG1_G_ZEN |
  545. CTRL_REG1_G_YEN |
  546. CTRL_REG1_G_XEN, true);
  547. hal.scheduler->delay(1);
  548. _register_write_g(CTRL_REG2_G, 0x00, true);
  549. hal.scheduler->delay(1);
  550. /*
  551. * Gyro data ready on DRDY_G
  552. */
  553. _register_write_g(CTRL_REG3_G, CTRL_REG3_G_I2_DRDY, true);
  554. hal.scheduler->delay(1);
  555. _register_write_g(CTRL_REG4_G,
  556. CTRL_REG4_G_BDU |
  557. CTRL_REG4_G_FS_2000DPS, true);
  558. _set_gyro_scale(G_SCALE_2000DPS);
  559. hal.scheduler->delay(1);
  560. _register_write_g(CTRL_REG5_G, 0x00, true);
  561. hal.scheduler->delay(1);
  562. }
  563. void AP_InertialSensor_LSM9DS0::_accel_init()
  564. {
  565. _accel_disable_i2c();
  566. hal.scheduler->delay(1);
  567. _register_write_xm(CTRL_REG0_XM, 0x00, true);
  568. hal.scheduler->delay(1);
  569. _register_write_xm(CTRL_REG1_XM,
  570. CTRL_REG1_XM_AODR_1600Hz |
  571. CTRL_REG1_XM_BDU |
  572. CTRL_REG1_XM_AZEN |
  573. CTRL_REG1_XM_AYEN |
  574. CTRL_REG1_XM_AXEN, true);
  575. hal.scheduler->delay(1);
  576. _register_write_xm(CTRL_REG2_XM,
  577. CTRL_REG2_XM_ABW_194Hz |
  578. CTRL_REG2_XM_AFS_16G, true);
  579. _set_accel_scale(A_SCALE_16G);
  580. hal.scheduler->delay(1);
  581. /* Accel data ready on INT1 */
  582. _register_write_xm(CTRL_REG3_XM, CTRL_REG3_XM_P1_DRDYA, true);
  583. hal.scheduler->delay(1);
  584. }
  585. void AP_InertialSensor_LSM9DS0::_set_gyro_scale(gyro_scale scale)
  586. {
  587. /* scales values from datasheet in mdps/digit */
  588. switch (scale) {
  589. case G_SCALE_245DPS:
  590. _gyro_scale = 8.75;
  591. break;
  592. case G_SCALE_500DPS:
  593. _gyro_scale = 17.50;
  594. break;
  595. case G_SCALE_2000DPS:
  596. _gyro_scale = 70;
  597. break;
  598. }
  599. /* convert mdps/digit to dps/digit */
  600. _gyro_scale /= 1000;
  601. /* convert dps/digit to (rad/s)/digit */
  602. _gyro_scale *= DEG_TO_RAD;
  603. }
  604. void AP_InertialSensor_LSM9DS0::_set_accel_scale(accel_scale scale)
  605. {
  606. /*
  607. * Possible accelerometer scales (and their register bit settings) are:
  608. * 2 g (000), 4g (001), 6g (010) 8g (011), 16g (100). Here's a bit of an
  609. * algorithm to calculate g/(ADC tick) based on that 3-bit value:
  610. */
  611. _accel_scale = (((float) scale + 1.0f) * 2.0f) / 32768.0f;
  612. if (scale == A_SCALE_16G) {
  613. /* the datasheet shows an exception for +-16G */
  614. _accel_scale = 0.000732f;
  615. }
  616. /* convert to G/LSB to (m/s/s)/LSB */
  617. _accel_scale *= GRAVITY_MSS;
  618. }
  619. /**
  620. * Timer process to poll for new data from the LSM9DS0.
  621. */
  622. void AP_InertialSensor_LSM9DS0::_poll_data()
  623. {
  624. if (_gyro_data_ready()) {
  625. _read_data_transaction_g();
  626. }
  627. if (_accel_data_ready()) {
  628. _read_data_transaction_a();
  629. }
  630. // check next register value for correctness
  631. if (!_dev_gyro->check_next_register()) {
  632. _inc_gyro_error_count(_gyro_instance);
  633. }
  634. if (!_dev_accel->check_next_register()) {
  635. _inc_accel_error_count(_accel_instance);
  636. }
  637. }
  638. bool AP_InertialSensor_LSM9DS0::_accel_data_ready()
  639. {
  640. if (_drdy_pin_a != nullptr) {
  641. return _drdy_pin_a->read() != 0;
  642. }
  643. uint8_t status = _register_read_xm(STATUS_REG_A);
  644. return status & STATUS_REG_A_ZYXADA;
  645. }
  646. bool AP_InertialSensor_LSM9DS0::_gyro_data_ready()
  647. {
  648. if (_drdy_pin_g != nullptr) {
  649. return _drdy_pin_g->read() != 0;
  650. }
  651. uint8_t status = _register_read_g(STATUS_REG_G);
  652. return status & STATUS_REG_G_ZYXDA;
  653. }
  654. void AP_InertialSensor_LSM9DS0::_read_data_transaction_a()
  655. {
  656. struct sensor_raw_data raw_data = { };
  657. const uint8_t reg = OUT_X_L_A | 0xC0;
  658. if (!_dev_accel->transfer(&reg, 1, (uint8_t *) &raw_data, sizeof(raw_data))) {
  659. hal.console->printf("LSM9DS0: error reading accelerometer\n");
  660. return;
  661. }
  662. Vector3f accel_data(raw_data.x, -raw_data.y, -raw_data.z);
  663. accel_data *= _accel_scale;
  664. _rotate_and_correct_accel(_accel_instance, accel_data);
  665. _notify_new_accel_raw_sample(_accel_instance, accel_data, AP_HAL::micros64());
  666. }
  667. /*
  668. * read from the data registers and update filtered data
  669. */
  670. void AP_InertialSensor_LSM9DS0::_read_data_transaction_g()
  671. {
  672. struct sensor_raw_data raw_data = { };
  673. const uint8_t reg = OUT_X_L_G | 0xC0;
  674. if (!_dev_gyro->transfer(&reg, 1, (uint8_t *) &raw_data, sizeof(raw_data))) {
  675. hal.console->printf("LSM9DS0: error reading gyroscope\n");
  676. return;
  677. }
  678. Vector3f gyro_data(raw_data.x, -raw_data.y, -raw_data.z);
  679. gyro_data *= _gyro_scale;
  680. _rotate_and_correct_gyro(_gyro_instance, gyro_data);
  681. _notify_new_gyro_raw_sample(_gyro_instance, gyro_data, AP_HAL::micros64());
  682. }
  683. bool AP_InertialSensor_LSM9DS0::update()
  684. {
  685. update_gyro(_gyro_instance);
  686. update_accel(_accel_instance);
  687. return true;
  688. }
  689. #if LSM9DS0_DEBUG
  690. /* dump all config registers - used for debug */
  691. void AP_InertialSensor_LSM9DS0::_dump_registers(void)
  692. {
  693. hal.console->printf("LSM9DS0 registers:\n");
  694. hal.console->printf("Gyroscope registers:\n");
  695. const uint8_t first = OUT_TEMP_L_XM;
  696. const uint8_t last = ACT_DUR;
  697. for (uint8_t reg=first; reg<=last; reg++) {
  698. uint8_t v = _register_read_g(reg);
  699. hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
  700. if ((reg - (first-1)) % 16 == 0) {
  701. hal.console->printf("\n");
  702. }
  703. }
  704. hal.console->printf("\n");
  705. hal.console->printf("Accelerometer and Magnetometers registers:\n");
  706. for (uint8_t reg=first; reg<=last; reg++) {
  707. uint8_t v = _register_read_xm(reg);
  708. hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
  709. if ((reg - (first-1)) % 16 == 0) {
  710. hal.console->printf("\n");
  711. }
  712. }
  713. hal.console->printf("\n");
  714. }
  715. #endif