AP_Compass.cpp 52 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  3. #include <AP_HAL_Linux/I2CDevice.h>
  4. #endif
  5. #include <AP_Vehicle/AP_Vehicle.h>
  6. #include <AP_BoardConfig/AP_BoardConfig.h>
  7. #include <AP_Logger/AP_Logger.h>
  8. #include "AP_Compass_SITL.h"
  9. #include "AP_Compass_AK8963.h"
  10. #include "AP_Compass_Backend.h"
  11. #include "AP_Compass_BMM150.h"
  12. #include "AP_Compass_HIL.h"
  13. #include "AP_Compass_HMC5843.h"
  14. #include "AP_Compass_IST8308.h"
  15. #include "AP_Compass_IST8310.h"
  16. #include "AP_Compass_LSM303D.h"
  17. #include "AP_Compass_LSM9DS1.h"
  18. #include "AP_Compass_LIS3MDL.h"
  19. #include "AP_Compass_AK09916.h"
  20. #include "AP_Compass_QMC5883L.h"
  21. #if HAL_WITH_UAVCAN
  22. #include "AP_Compass_UAVCAN.h"
  23. #endif
  24. #include "AP_Compass_MMC3416.h"
  25. #include "AP_Compass_MAG3110.h"
  26. #include "AP_Compass_RM3100.h"
  27. #include "AP_Compass.h"
  28. #include "Compass_learn.h"
  29. extern AP_HAL::HAL& hal;
  30. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  31. #define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
  32. #else
  33. #define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL
  34. #endif
  35. #ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
  36. #define AP_COMPASS_OFFSETS_MAX_DEFAULT 1800
  37. #endif
  38. #ifndef HAL_COMPASS_FILTER_DEFAULT
  39. #define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default
  40. #endif
  41. #ifndef HAL_COMPASS_AUTO_ROT_DEFAULT
  42. #define HAL_COMPASS_AUTO_ROT_DEFAULT 2
  43. #endif
  44. const AP_Param::GroupInfo Compass::var_info[] = {
  45. // index 0 was used for the old orientation matrix
  46. // @Param: OFS_X
  47. // @DisplayName: Compass offsets in milligauss on the X axis
  48. // @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
  49. // @Range: -400 400
  50. // @Units: mGauss
  51. // @Increment: 1
  52. // @User: Advanced
  53. // @Param: OFS_Y
  54. // @DisplayName: Compass offsets in milligauss on the Y axis
  55. // @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame
  56. // @Range: -400 400
  57. // @Units: mGauss
  58. // @Increment: 1
  59. // @User: Advanced
  60. // @Param: OFS_Z
  61. // @DisplayName: Compass offsets in milligauss on the Z axis
  62. // @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame
  63. // @Range: -400 400
  64. // @Units: mGauss
  65. // @Increment: 1
  66. // @User: Advanced
  67. AP_GROUPINFO("OFS", 1, Compass, _state[0].offset, 0),
  68. // @Param: DEC
  69. // @DisplayName: Compass declination
  70. // @Description: An angle to compensate between the true north and magnetic north
  71. // @Range: -3.142 3.142
  72. // @Units: rad
  73. // @Increment: 0.01
  74. // @User: Standard
  75. AP_GROUPINFO("DEC", 2, Compass, _declination, 0),
  76. // @Param: LEARN
  77. // @DisplayName: Learn compass offsets automatically
  78. // @Description: Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
  79. // @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning,3:InFlight-Learning
  80. // @User: Advanced
  81. AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),
  82. // @Param: USE
  83. // @DisplayName: Use compass for yaw
  84. // @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading
  85. // @Values: 0:Disabled,1:Enabled
  86. // @User: Advanced
  87. AP_GROUPINFO("USE", 4, Compass, _state[0].use_for_yaw, 1), // true if used for DCM yaw
  88. // @Param: AUTODEC
  89. // @DisplayName: Auto Declination
  90. // @Description: Enable or disable the automatic calculation of the declination based on gps location
  91. // @Values: 0:Disabled,1:Enabled
  92. // @User: Advanced
  93. AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1),
  94. // @Param: MOTCT
  95. // @DisplayName: Motor interference compensation type
  96. // @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually.
  97. // @Values: 0:Disabled,1:Use Throttle,2:Use Current
  98. // @User: Advanced
  99. AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED),
  100. // @Param: MOT_X
  101. // @DisplayName: Motor interference compensation for body frame X axis
  102. // @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  103. // @Range: -1000 1000
  104. // @Units: mGauss/A
  105. // @Increment: 1
  106. // @User: Advanced
  107. // @Param: MOT_Y
  108. // @DisplayName: Motor interference compensation for body frame Y axis
  109. // @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  110. // @Range: -1000 1000
  111. // @Units: mGauss/A
  112. // @Increment: 1
  113. // @User: Advanced
  114. // @Param: MOT_Z
  115. // @DisplayName: Motor interference compensation for body frame Z axis
  116. // @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  117. // @Range: -1000 1000
  118. // @Units: mGauss/A
  119. // @Increment: 1
  120. // @User: Advanced
  121. AP_GROUPINFO("MOT", 7, Compass, _state[0].motor_compensation, 0),
  122. // @Param: ORIENT
  123. // @DisplayName: Compass orientation
  124. // @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
  125. // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
  126. // @User: Advanced
  127. AP_GROUPINFO("ORIENT", 8, Compass, _state[0].orientation, ROTATION_NONE),
  128. // @Param: EXTERNAL
  129. // @DisplayName: Compass is attached via an external cable
  130. // @Description: Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
  131. // @Values: 0:Internal,1:External,2:ForcedExternal
  132. // @User: Advanced
  133. AP_GROUPINFO("EXTERNAL", 9, Compass, _state[0].external, 0),
  134. // @Param: OFS2_X
  135. // @DisplayName: Compass2 offsets in milligauss on the X axis
  136. // @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame
  137. // @Range: -400 400
  138. // @Units: mGauss
  139. // @Increment: 1
  140. // @User: Advanced
  141. // @Param: OFS2_Y
  142. // @DisplayName: Compass2 offsets in milligauss on the Y axis
  143. // @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame
  144. // @Range: -400 400
  145. // @Units: mGauss
  146. // @Increment: 1
  147. // @User: Advanced
  148. // @Param: OFS2_Z
  149. // @DisplayName: Compass2 offsets in milligauss on the Z axis
  150. // @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame
  151. // @Range: -400 400
  152. // @Units: mGauss
  153. // @Increment: 1
  154. // @User: Advanced
  155. AP_GROUPINFO("OFS2", 10, Compass, _state[1].offset, 0),
  156. // @Param: MOT2_X
  157. // @DisplayName: Motor interference compensation to compass2 for body frame X axis
  158. // @Description: Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  159. // @Range: -1000 1000
  160. // @Units: mGauss/A
  161. // @Increment: 1
  162. // @User: Advanced
  163. // @Param: MOT2_Y
  164. // @DisplayName: Motor interference compensation to compass2 for body frame Y axis
  165. // @Description: Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  166. // @Range: -1000 1000
  167. // @Units: mGauss/A
  168. // @Increment: 1
  169. // @User: Advanced
  170. // @Param: MOT2_Z
  171. // @DisplayName: Motor interference compensation to compass2 for body frame Z axis
  172. // @Description: Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  173. // @Range: -1000 1000
  174. // @Units: mGauss/A
  175. // @Increment: 1
  176. // @User: Advanced
  177. AP_GROUPINFO("MOT2", 11, Compass, _state[1].motor_compensation, 0),
  178. // @Param: PRIMARY
  179. // @DisplayName: Choose primary compass
  180. // @Description: If more than one compass is available, this selects which compass is the primary. When external compasses are connected, they will be ordered first. NOTE: If no external compass is attached, this parameter is ignored.
  181. // @Values: 0:FirstCompass,1:SecondCompass,2:ThirdCompass
  182. // @User: Advanced
  183. AP_GROUPINFO("PRIMARY", 12, Compass, _primary, 0),
  184. // @Param: OFS3_X
  185. // @DisplayName: Compass3 offsets in milligauss on the X axis
  186. // @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame
  187. // @Range: -400 400
  188. // @Units: mGauss
  189. // @Increment: 1
  190. // @User: Advanced
  191. // @Param: OFS3_Y
  192. // @DisplayName: Compass3 offsets in milligauss on the Y axis
  193. // @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame
  194. // @Range: -400 400
  195. // @Units: mGauss
  196. // @Increment: 1
  197. // @User: Advanced
  198. // @Param: OFS3_Z
  199. // @DisplayName: Compass3 offsets in milligauss on the Z axis
  200. // @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame
  201. // @Range: -400 400
  202. // @Units: mGauss
  203. // @Increment: 1
  204. // @User: Advanced
  205. AP_GROUPINFO("OFS3", 13, Compass, _state[2].offset, 0),
  206. // @Param: MOT3_X
  207. // @DisplayName: Motor interference compensation to compass3 for body frame X axis
  208. // @Description: Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  209. // @Range: -1000 1000
  210. // @Units: mGauss/A
  211. // @Increment: 1
  212. // @User: Advanced
  213. // @Param: MOT3_Y
  214. // @DisplayName: Motor interference compensation to compass3 for body frame Y axis
  215. // @Description: Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  216. // @Range: -1000 1000
  217. // @Units: mGauss/A
  218. // @Increment: 1
  219. // @User: Advanced
  220. // @Param: MOT3_Z
  221. // @DisplayName: Motor interference compensation to compass3 for body frame Z axis
  222. // @Description: Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
  223. // @Range: -1000 1000
  224. // @Units: mGauss/A
  225. // @Increment: 1
  226. // @User: Advanced
  227. AP_GROUPINFO("MOT3", 14, Compass, _state[2].motor_compensation, 0),
  228. // @Param: DEV_ID
  229. // @DisplayName: Compass device id
  230. // @Description: Compass device id. Automatically detected, do not set manually
  231. // @ReadOnly: True
  232. // @User: Advanced
  233. AP_GROUPINFO("DEV_ID", 15, Compass, _state[0].dev_id, 0),
  234. // @Param: DEV_ID2
  235. // @DisplayName: Compass2 device id
  236. // @Description: Second compass's device id. Automatically detected, do not set manually
  237. // @ReadOnly: True
  238. // @User: Advanced
  239. AP_GROUPINFO("DEV_ID2", 16, Compass, _state[1].dev_id, 0),
  240. // @Param: DEV_ID3
  241. // @DisplayName: Compass3 device id
  242. // @Description: Third compass's device id. Automatically detected, do not set manually
  243. // @ReadOnly: True
  244. // @User: Advanced
  245. AP_GROUPINFO("DEV_ID3", 17, Compass, _state[2].dev_id, 0),
  246. // @Param: USE2
  247. // @DisplayName: Compass2 used for yaw
  248. // @Description: Enable or disable the second compass for determining heading.
  249. // @Values: 0:Disabled,1:Enabled
  250. // @User: Advanced
  251. AP_GROUPINFO("USE2", 18, Compass, _state[1].use_for_yaw, 1),
  252. // @Param: ORIENT2
  253. // @DisplayName: Compass2 orientation
  254. // @Description: The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
  255. // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
  256. // @User: Advanced
  257. AP_GROUPINFO("ORIENT2", 19, Compass, _state[1].orientation, ROTATION_NONE),
  258. // @Param: EXTERN2
  259. // @DisplayName: Compass2 is attached via an external cable
  260. // @Description: Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
  261. // @Values: 0:Internal,1:External,2:ForcedExternal
  262. // @User: Advanced
  263. AP_GROUPINFO("EXTERN2",20, Compass, _state[1].external, 0),
  264. // @Param: USE3
  265. // @DisplayName: Compass3 used for yaw
  266. // @Description: Enable or disable the third compass for determining heading.
  267. // @Values: 0:Disabled,1:Enabled
  268. // @User: Advanced
  269. AP_GROUPINFO("USE3", 21, Compass, _state[2].use_for_yaw, 1),
  270. // @Param: ORIENT3
  271. // @DisplayName: Compass3 orientation
  272. // @Description: The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
  273. // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
  274. // @User: Advanced
  275. AP_GROUPINFO("ORIENT3", 22, Compass, _state[2].orientation, ROTATION_NONE),
  276. // @Param: EXTERN3
  277. // @DisplayName: Compass3 is attached via an external cable
  278. // @Description: Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
  279. // @Values: 0:Internal,1:External,2:ForcedExternal
  280. // @User: Advanced
  281. AP_GROUPINFO("EXTERN3",23, Compass, _state[2].external, 0),
  282. // @Param: DIA_X
  283. // @DisplayName: Compass soft-iron diagonal X component
  284. // @Description: DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  285. // @User: Advanced
  286. // @Param: DIA_Y
  287. // @DisplayName: Compass soft-iron diagonal Y component
  288. // @Description: DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  289. // @User: Advanced
  290. // @Param: DIA_Z
  291. // @DisplayName: Compass soft-iron diagonal Z component
  292. // @Description: DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  293. // @User: Advanced
  294. AP_GROUPINFO("DIA", 24, Compass, _state[0].diagonals, 0),
  295. // @Param: ODI_X
  296. // @DisplayName: Compass soft-iron off-diagonal X component
  297. // @Description: ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  298. // @User: Advanced
  299. // @Param: ODI_Y
  300. // @DisplayName: Compass soft-iron off-diagonal Y component
  301. // @Description: ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  302. // @User: Advanced
  303. // @Param: ODI_Z
  304. // @DisplayName: Compass soft-iron off-diagonal Z component
  305. // @Description: ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  306. // @User: Advanced
  307. AP_GROUPINFO("ODI", 25, Compass, _state[0].offdiagonals, 0),
  308. // @Param: DIA2_X
  309. // @DisplayName: Compass2 soft-iron diagonal X component
  310. // @Description: DIA_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  311. // @User: Advanced
  312. // @Param: DIA2_Y
  313. // @DisplayName: Compass2 soft-iron diagonal Y component
  314. // @Description: DIA_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  315. // @User: Advanced
  316. // @Param: DIA2_Z
  317. // @DisplayName: Compass2 soft-iron diagonal Z component
  318. // @Description: DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  319. // @User: Advanced
  320. AP_GROUPINFO("DIA2", 26, Compass, _state[1].diagonals, 0),
  321. // @Param: ODI2_X
  322. // @DisplayName: Compass2 soft-iron off-diagonal X component
  323. // @Description: ODI_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  324. // @User: Advanced
  325. // @Param: ODI2_Y
  326. // @DisplayName: Compass2 soft-iron off-diagonal Y component
  327. // @Description: ODI_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  328. // @User: Advanced
  329. // @Param: ODI2_Z
  330. // @DisplayName: Compass2 soft-iron off-diagonal Z component
  331. // @Description: ODI_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  332. // @User: Advanced
  333. AP_GROUPINFO("ODI2", 27, Compass, _state[1].offdiagonals, 0),
  334. // @Param: DIA3_X
  335. // @DisplayName: Compass3 soft-iron diagonal X component
  336. // @Description: DIA_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  337. // @User: Advanced
  338. // @Param: DIA3_Y
  339. // @DisplayName: Compass3 soft-iron diagonal Y component
  340. // @Description: DIA_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  341. // @User: Advanced
  342. // @Param: DIA3_Z
  343. // @DisplayName: Compass3 soft-iron diagonal Z component
  344. // @Description: DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  345. // @User: Advanced
  346. AP_GROUPINFO("DIA3", 28, Compass, _state[2].diagonals, 0),
  347. // @Param: ODI3_X
  348. // @DisplayName: Compass3 soft-iron off-diagonal X component
  349. // @Description: ODI_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  350. // @User: Advanced
  351. // @Param: ODI3_Y
  352. // @DisplayName: Compass3 soft-iron off-diagonal Y component
  353. // @Description: ODI_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  354. // @User: Advanced
  355. // @Param: ODI3_Z
  356. // @DisplayName: Compass3 soft-iron off-diagonal Z component
  357. // @Description: ODI_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
  358. // @User: Advanced
  359. AP_GROUPINFO("ODI3", 29, Compass, _state[2].offdiagonals, 0),
  360. // @Param: CAL_FIT
  361. // @DisplayName: Compass calibration fitness
  362. // @Description: This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.
  363. // @Range: 4 32
  364. // @Values: 4:Very Strict,8:Strict,16:Default,32:Relaxed
  365. // @Increment: 0.1
  366. // @User: Advanced
  367. AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT),
  368. // @Param: OFFS_MAX
  369. // @DisplayName: Compass maximum offset
  370. // @Description: This sets the maximum allowed compass offset in calibration and arming checks
  371. // @Range: 500 3000
  372. // @Increment: 1
  373. // @User: Advanced
  374. AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT),
  375. #if COMPASS_MOT_ENABLED
  376. // @Group: PMOT
  377. // @Path: Compass_PerMotor.cpp
  378. AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor),
  379. #endif
  380. // @Param: TYPEMASK
  381. // @DisplayName: Compass disable driver type mask
  382. // @Description: This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
  383. // @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:UAVCAN,12:QMC5883,14:MAG3110,15:IST8308
  384. // @User: Advanced
  385. AP_GROUPINFO("TYPEMASK", 33, Compass, _driver_type_mask, 0),
  386. // @Param: FLTR_RNG
  387. // @DisplayName: Range in which sample is accepted
  388. // @Description: This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
  389. // @Units: %
  390. // @Range: 0 100
  391. // @Increment: 1
  392. AP_GROUPINFO("FLTR_RNG", 34, Compass, _filter_range, HAL_COMPASS_FILTER_DEFAULT),
  393. // @Param: AUTO_ROT
  394. // @DisplayName: Automatically check orientation
  395. // @Description: When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
  396. // @Values: 0:Disabled,1:CheckOnly,2:CheckAndFix
  397. AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT),
  398. // @Param: EXP_DID
  399. // @DisplayName: Compass device id expected
  400. // @Description: The expected value of COMPASS_DEV_ID, used by arming checks. Setting this to -1 means "don't care."
  401. // @User: Advanced
  402. AP_GROUPINFO("EXP_DID", 36, Compass, _state[0].expected_dev_id, -1),
  403. // @Param: EXP_DID2
  404. // @DisplayName: Compass2 device id expected
  405. // @Description: The expected value of COMPASS_DEV_ID2, used by arming checks. Setting this to -1 means "don't care."
  406. // @User: Advanced
  407. AP_GROUPINFO("EXP_DID2", 37, Compass, _state[1].expected_dev_id, -1),
  408. // @Param: EXP_DID3
  409. // @DisplayName: Compass3 device id expected
  410. // @Description: The expected value of COMPASS_DEV_ID3, used by arming checks. Setting this to -1 means "don't care."
  411. // @User: Advanced
  412. AP_GROUPINFO("EXP_DID3", 38, Compass, _state[2].expected_dev_id, -1),
  413. // @Param: ENABLE
  414. // @DisplayName: Enable Compass
  415. // @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
  416. // @User: Standard
  417. // @Values: 0:Disabled,1:Enabled
  418. AP_GROUPINFO("ENABLE", 39, Compass, _enabled, 1),
  419. AP_GROUPEND
  420. };
  421. // Default constructor.
  422. // Note that the Vector/Matrix constructors already implicitly zero
  423. // their values.
  424. //
  425. Compass::Compass(void)
  426. {
  427. if (_singleton != nullptr) {
  428. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  429. AP_HAL::panic("Compass must be singleton");
  430. #endif
  431. return;
  432. }
  433. _singleton = this;
  434. AP_Param::setup_object_defaults(this, var_info);
  435. }
  436. // Default init method
  437. //
  438. void Compass::init()
  439. {
  440. if (!AP::compass().enabled()) {
  441. return;
  442. }
  443. if (_compass_count == 0) {
  444. // detect available backends. Only called once
  445. _detect_backends();
  446. }
  447. if (_compass_count != 0) {
  448. // get initial health status
  449. hal.scheduler->delay(100);
  450. read();
  451. }
  452. // set the dev_id to 0 for undetected compasses, to make it easier
  453. // for users to see how many compasses are detected. We don't do a
  454. // set_and_save() as the user may have temporarily removed the
  455. // compass, and we don't want to force a re-cal if they plug it
  456. // back in again
  457. for (uint8_t i=_compass_count; i<COMPASS_MAX_INSTANCES; i++) {
  458. _state[i].dev_id.set(0);
  459. }
  460. // check that we are actually working before passing the compass
  461. // through to ARHS to use.
  462. if (!read()) {
  463. #ifndef HAL_BUILD_AP_PERIPH
  464. _enabled = false;
  465. hal.console->printf("Compass initialisation failed\n");
  466. #endif
  467. #ifndef HAL_NO_LOGGING
  468. AP::logger().Write_Error(LogErrorSubsystem::COMPASS, LogErrorCode::FAILED_TO_INITIALISE);
  469. #endif
  470. return;
  471. }
  472. #ifndef HAL_BUILD_AP_PERIPH
  473. AP::ahrs().set_compass(this);
  474. #endif
  475. }
  476. // Register a new compass instance
  477. //
  478. uint8_t Compass::register_compass(void)
  479. {
  480. if (_compass_count == COMPASS_MAX_INSTANCES) {
  481. AP_HAL::panic("Too many compass instances");
  482. }
  483. return _compass_count++;
  484. }
  485. bool Compass::_add_backend(AP_Compass_Backend *backend)
  486. {
  487. if (!backend) {
  488. return false;
  489. }
  490. if (_backend_count == COMPASS_MAX_BACKEND) {
  491. AP_HAL::panic("Too many compass backends");
  492. }
  493. _backends[_backend_count++] = backend;
  494. return true;
  495. }
  496. /*
  497. return true if a driver type is enabled
  498. */
  499. bool Compass::_driver_enabled(enum DriverType driver_type)
  500. {
  501. uint32_t mask = (1U<<uint8_t(driver_type));
  502. return (mask & uint32_t(_driver_type_mask.get())) == 0;
  503. }
  504. /*
  505. wrapper around hal.i2c_mgr->get_device() that prevents duplicate devices being opened
  506. */
  507. bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const
  508. {
  509. for (uint8_t i=0; i<_compass_count; i++) {
  510. if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==
  511. AP_HAL::Device::change_bus_id(uint32_t(_state[i].dev_id.get()), 0)) {
  512. // we are already using this device
  513. return true;
  514. }
  515. }
  516. return false;
  517. }
  518. /*
  519. macro to add a backend with check for too many backends or compass
  520. instances. We don't try to start more than the maximum allowed
  521. */
  522. #define ADD_BACKEND(driver_type, backend) \
  523. do { if (_driver_enabled(driver_type)) { _add_backend(backend); } \
  524. if (_backend_count == COMPASS_MAX_BACKEND || \
  525. _compass_count == COMPASS_MAX_INSTANCES) { \
  526. return; \
  527. } \
  528. } while (0)
  529. #define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address)
  530. /*
  531. look for compasses on external i2c buses
  532. */
  533. void Compass::_probe_external_i2c_compasses(void)
  534. {
  535. bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
  536. // external i2c bus
  537. FOREACH_I2C_EXTERNAL(i) {
  538. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
  539. true, ROTATION_ROLL_180));
  540. }
  541. if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2 &&
  542. AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) {
  543. // internal i2c bus
  544. FOREACH_I2C_INTERNAL(i) {
  545. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
  546. all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270));
  547. }
  548. }
  549. //external i2c bus
  550. FOREACH_I2C_EXTERNAL(i) {
  551. ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
  552. true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL));
  553. }
  554. // internal i2c bus
  555. if (all_external) {
  556. // only probe QMC5883L on internal if we are treating internals as externals
  557. FOREACH_I2C_INTERNAL(i) {
  558. ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
  559. all_external,
  560. all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
  561. }
  562. }
  563. #if !HAL_MINIMIZE_FEATURES
  564. // AK09916 on ICM20948
  565. FOREACH_I2C_EXTERNAL(i) {
  566. ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
  567. GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
  568. true, ROTATION_PITCH_180_YAW_90));
  569. }
  570. FOREACH_I2C_INTERNAL(i) {
  571. ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
  572. GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
  573. all_external, ROTATION_PITCH_180_YAW_90));
  574. }
  575. // lis3mdl on bus 0 with default address
  576. FOREACH_I2C_INTERNAL(i) {
  577. ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
  578. all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
  579. }
  580. // lis3mdl on bus 0 with alternate address
  581. FOREACH_I2C_INTERNAL(i) {
  582. ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
  583. all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
  584. }
  585. // external lis3mdl on bus 1 with default address
  586. FOREACH_I2C_EXTERNAL(i) {
  587. ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
  588. true, ROTATION_YAW_90));
  589. }
  590. // external lis3mdl on bus 1 with alternate address
  591. FOREACH_I2C_EXTERNAL(i) {
  592. ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
  593. true, ROTATION_YAW_90));
  594. }
  595. // AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that
  596. FOREACH_I2C_EXTERNAL(i) {
  597. ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
  598. true, ROTATION_YAW_270));
  599. }
  600. FOREACH_I2C_INTERNAL(i) {
  601. ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
  602. all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));
  603. }
  604. // IST8310 on external and internal bus
  605. if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 &&
  606. AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) {
  607. enum Rotation default_rotation;
  608. if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) {
  609. default_rotation = ROTATION_PITCH_180_YAW_90;
  610. } else {
  611. default_rotation = ROTATION_PITCH_180;
  612. }
  613. // probe all 4 possible addresses
  614. const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F };
  615. for (uint8_t a=0; a<ARRAY_SIZE(ist8310_addr); a++) {
  616. FOREACH_I2C_EXTERNAL(i) {
  617. ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
  618. true, default_rotation));
  619. }
  620. FOREACH_I2C_INTERNAL(i) {
  621. ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
  622. all_external, default_rotation));
  623. }
  624. }
  625. }
  626. // external i2c bus
  627. FOREACH_I2C_EXTERNAL(i) {
  628. ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
  629. true, ROTATION_NONE));
  630. }
  631. #endif // HAL_MINIMIZE_FEATURES
  632. }
  633. /*
  634. detect available backends for this board
  635. */
  636. void Compass::_detect_backends(void)
  637. {
  638. if (_hil_mode) {
  639. _add_backend(AP_Compass_HIL::detect());
  640. return;
  641. }
  642. #if AP_FEATURE_BOARD_DETECT
  643. if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
  644. // default to disabling LIS3MDL on pixhawk2 due to hardware issue
  645. _driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);
  646. }
  647. #endif
  648. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  649. ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL());
  650. return;
  651. #endif
  652. #ifdef HAL_PROBE_EXTERNAL_I2C_COMPASSES
  653. // allow boards to ask for external probing of all i2c compass types in hwdef.dat
  654. _probe_external_i2c_compasses();
  655. if (_backend_count == COMPASS_MAX_BACKEND ||
  656. _compass_count == COMPASS_MAX_INSTANCES) {
  657. return;
  658. }
  659. #endif
  660. #if defined(HAL_MAG_PROBE_LIST)
  661. // driver probes defined by COMPASS lines in hwdef.dat
  662. HAL_MAG_PROBE_LIST;
  663. #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
  664. ADD_BACKEND(DRIVER_SITL, AP_Compass_HIL::detect());
  665. #elif AP_FEATURE_BOARD_DETECT
  666. switch (AP_BoardConfig::get_board_type()) {
  667. case AP_BoardConfig::PX4_BOARD_PX4V1:
  668. case AP_BoardConfig::PX4_BOARD_PIXHAWK:
  669. case AP_BoardConfig::PX4_BOARD_PHMINI:
  670. case AP_BoardConfig::PX4_BOARD_AUAV21:
  671. case AP_BoardConfig::PX4_BOARD_PH2SLIM:
  672. case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
  673. case AP_BoardConfig::PX4_BOARD_MINDPXV2:
  674. case AP_BoardConfig::PX4_BOARD_FMUV5:
  675. case AP_BoardConfig::PX4_BOARD_FMUV6:
  676. case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
  677. case AP_BoardConfig::PX4_BOARD_AEROFC:
  678. _probe_external_i2c_compasses();
  679. if (_backend_count == COMPASS_MAX_BACKEND ||
  680. _compass_count == COMPASS_MAX_INSTANCES) {
  681. return;
  682. }
  683. break;
  684. case AP_BoardConfig::PX4_BOARD_PCNC1:
  685. ADD_BACKEND(DRIVER_BMM150,
  686. AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), ROTATION_NONE));
  687. break;
  688. case AP_BoardConfig::VRX_BOARD_BRAIN54: {
  689. // external i2c bus
  690. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
  691. true, ROTATION_ROLL_180));
  692. }
  693. // internal i2c bus
  694. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
  695. false, ROTATION_YAW_270));
  696. break;
  697. case AP_BoardConfig::VRX_BOARD_BRAIN51:
  698. case AP_BoardConfig::VRX_BOARD_BRAIN52:
  699. case AP_BoardConfig::VRX_BOARD_BRAIN52E:
  700. case AP_BoardConfig::VRX_BOARD_CORE10:
  701. case AP_BoardConfig::VRX_BOARD_UBRAIN51:
  702. case AP_BoardConfig::VRX_BOARD_UBRAIN52: {
  703. // external i2c bus
  704. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
  705. true, ROTATION_ROLL_180));
  706. }
  707. break;
  708. default:
  709. break;
  710. }
  711. switch (AP_BoardConfig::get_board_type()) {
  712. case AP_BoardConfig::PX4_BOARD_PIXHAWK:
  713. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
  714. false, ROTATION_PITCH_180));
  715. ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_NONE));
  716. break;
  717. case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
  718. ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270));
  719. // we run the AK8963 only on the 2nd MPU9250, which leaves the
  720. // first MPU9250 to run without disturbance at high rate
  721. ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
  722. ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
  723. break;
  724. case AP_BoardConfig::PX4_BOARD_FMUV5:
  725. case AP_BoardConfig::PX4_BOARD_FMUV6:
  726. FOREACH_I2C_EXTERNAL(i) {
  727. ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
  728. true, ROTATION_ROLL_180_YAW_90));
  729. }
  730. FOREACH_I2C_INTERNAL(i) {
  731. ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
  732. false, ROTATION_ROLL_180_YAW_90));
  733. }
  734. break;
  735. case AP_BoardConfig::PX4_BOARD_SP01:
  736. ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));
  737. break;
  738. case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
  739. ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
  740. ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
  741. false, ROTATION_NONE));
  742. break;
  743. case AP_BoardConfig::PX4_BOARD_PHMINI:
  744. ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180));
  745. break;
  746. case AP_BoardConfig::PX4_BOARD_AUAV21:
  747. ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
  748. break;
  749. case AP_BoardConfig::PX4_BOARD_PH2SLIM:
  750. ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270));
  751. break;
  752. case AP_BoardConfig::PX4_BOARD_MINDPXV2:
  753. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
  754. false, ROTATION_YAW_90));
  755. ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270));
  756. break;
  757. default:
  758. break;
  759. }
  760. #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NONE
  761. // no compass, or only external probe
  762. #else
  763. #error Unrecognised HAL_COMPASS_TYPE setting
  764. #endif
  765. /* for chibios external board coniguration */
  766. #ifdef HAL_EXT_COMPASS_HMC5843_I2C_BUS
  767. ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(HAL_EXT_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR),
  768. true, ROTATION_ROLL_180));
  769. #endif
  770. #if HAL_WITH_UAVCAN
  771. for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) {
  772. ADD_BACKEND(DRIVER_UAVCAN, AP_Compass_UAVCAN::probe());
  773. }
  774. #endif
  775. if (_backend_count == 0 ||
  776. _compass_count == 0) {
  777. hal.console->printf("No Compass backends available\n");
  778. }
  779. }
  780. bool
  781. Compass::read(void)
  782. {
  783. #ifndef HAL_BUILD_AP_PERIPH
  784. if (!_initial_location_set) {
  785. try_set_initial_location();
  786. }
  787. #endif
  788. for (uint8_t i=0; i< _backend_count; i++) {
  789. // call read on each of the backend. This call updates field[i]
  790. _backends[i]->read();
  791. }
  792. uint32_t time = AP_HAL::millis();
  793. for (uint8_t i=0; i < COMPASS_MAX_INSTANCES; i++) {
  794. _state[i].healthy = (time - _state[i].last_update_ms < 500);
  795. }
  796. #if COMPASS_LEARN_ENABLED
  797. if (_learn == LEARN_INFLIGHT && !learn_allocated) {
  798. learn_allocated = true;
  799. learn = new CompassLearn(*this);
  800. }
  801. if (_learn == LEARN_INFLIGHT && learn != nullptr) {
  802. learn->update();
  803. }
  804. bool ret = healthy();
  805. if (ret && _log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit) && !AP::ahrs().have_ekf_logging()) {
  806. AP::logger().Write_Compass();
  807. }
  808. return ret;
  809. #else
  810. return healthy();
  811. #endif
  812. }
  813. uint8_t
  814. Compass::get_healthy_mask() const
  815. {
  816. uint8_t healthy_mask = 0;
  817. for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  818. if(healthy(i)) {
  819. healthy_mask |= 1 << i;
  820. }
  821. }
  822. return healthy_mask;
  823. }
  824. void
  825. Compass::set_offsets(uint8_t i, const Vector3f &offsets)
  826. {
  827. // sanity check compass instance provided
  828. if (i < COMPASS_MAX_INSTANCES) {
  829. _state[i].offset.set(offsets);
  830. }
  831. }
  832. void
  833. Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
  834. {
  835. // sanity check compass instance provided
  836. if (i < COMPASS_MAX_INSTANCES) {
  837. _state[i].offset.set(offsets);
  838. save_offsets(i);
  839. }
  840. }
  841. void
  842. Compass::set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
  843. {
  844. // sanity check compass instance provided
  845. if (i < COMPASS_MAX_INSTANCES) {
  846. _state[i].diagonals.set_and_save(diagonals);
  847. }
  848. }
  849. void
  850. Compass::set_and_save_offdiagonals(uint8_t i, const Vector3f &offdiagonals)
  851. {
  852. // sanity check compass instance provided
  853. if (i < COMPASS_MAX_INSTANCES) {
  854. _state[i].offdiagonals.set_and_save(offdiagonals);
  855. }
  856. }
  857. void
  858. Compass::save_offsets(uint8_t i)
  859. {
  860. _state[i].offset.save(); // save offsets
  861. _state[i].dev_id.set_and_save(_state[i].detected_dev_id);
  862. }
  863. void
  864. Compass::save_offsets(void)
  865. {
  866. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  867. save_offsets(i);
  868. }
  869. }
  870. void
  871. Compass::set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
  872. {
  873. _state[i].motor_compensation.set(motor_comp_factor);
  874. }
  875. void
  876. Compass::save_motor_compensation()
  877. {
  878. _motor_comp_type.save();
  879. for (uint8_t k=0; k<COMPASS_MAX_INSTANCES; k++) {
  880. _state[k].motor_compensation.save();
  881. }
  882. }
  883. void Compass::try_set_initial_location()
  884. {
  885. if (!_auto_declination) {
  886. return;
  887. }
  888. if (!_enabled) {
  889. return;
  890. }
  891. Location loc;
  892. if (!AP::ahrs().get_position(loc)) {
  893. return;
  894. }
  895. _initial_location_set = true;
  896. // if automatic declination is configured, then compute
  897. // the declination based on the initial GPS fix
  898. // Set the declination based on the lat/lng from GPS
  899. _declination.set(radians(
  900. AP_Declination::get_declination(
  901. (float)loc.lat / 10000000,
  902. (float)loc.lng / 10000000)));
  903. }
  904. /// return true if the compass should be used for yaw calculations
  905. bool
  906. Compass::use_for_yaw(void) const
  907. {
  908. uint8_t prim = get_primary();
  909. return healthy(prim) && use_for_yaw(prim);
  910. }
  911. /// return true if the specified compass can be used for yaw calculations
  912. bool
  913. Compass::use_for_yaw(uint8_t i) const
  914. {
  915. // when we are doing in-flight compass learning the state
  916. // estimator must not use the compass. The learning code turns off
  917. // inflight learning when it has converged
  918. return _state[i].use_for_yaw && _learn.get() != LEARN_INFLIGHT;
  919. }
  920. void
  921. Compass::set_declination(float radians, bool save_to_eeprom)
  922. {
  923. if (save_to_eeprom) {
  924. _declination.set_and_save(radians);
  925. }else{
  926. _declination.set(radians);
  927. }
  928. }
  929. float
  930. Compass::get_declination() const
  931. {
  932. return _declination.get();
  933. }
  934. /*
  935. calculate a compass heading given the attitude from DCM and the mag vector
  936. */
  937. float
  938. Compass::calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const
  939. {
  940. float cos_pitch_sq = 1.0f-(dcm_matrix.c.x*dcm_matrix.c.x);
  941. // Tilt compensated magnetic field Y component:
  942. const Vector3f &field = get_field(i);
  943. float headY = field.y * dcm_matrix.c.z - field.z * dcm_matrix.c.y;
  944. // Tilt compensated magnetic field X component:
  945. float headX = field.x * cos_pitch_sq - dcm_matrix.c.x * (field.y * dcm_matrix.c.y + field.z * dcm_matrix.c.z);
  946. // magnetic heading
  947. // 6/4/11 - added constrain to keep bad values from ruining DCM Yaw - Jason S.
  948. float heading = constrain_float(atan2f(-headY,headX), -3.15f, 3.15f);
  949. // Declination correction (if supplied)
  950. if( fabsf(_declination) > 0.0f )
  951. {
  952. heading = heading + _declination;
  953. if (heading > M_PI) // Angle normalization (-180 deg, 180 deg)
  954. heading -= (2.0f * M_PI);
  955. else if (heading < -M_PI)
  956. heading += (2.0f * M_PI);
  957. }
  958. return heading;
  959. }
  960. /// Returns True if the compasses have been configured (i.e. offsets saved)
  961. ///
  962. /// @returns True if compass has been configured
  963. ///
  964. bool Compass::configured(uint8_t i)
  965. {
  966. // exit immediately if instance is beyond the number of compasses we have available
  967. if (i > get_count()) {
  968. return false;
  969. }
  970. // exit immediately if all offsets are zero
  971. if (is_zero(get_offsets(i).length())) {
  972. return false;
  973. }
  974. // exit immediately if dev_id hasn't been detected
  975. if (_state[i].detected_dev_id == 0) {
  976. return false;
  977. }
  978. // back up cached value of dev_id
  979. int32_t dev_id_cache_value = _state[i].dev_id;
  980. // load dev_id from eeprom
  981. _state[i].dev_id.load();
  982. // if dev_id loaded from eeprom is different from detected dev id or dev_id loaded from eeprom is different from cached dev_id, compass is unconfigured
  983. if (_state[i].dev_id != _state[i].detected_dev_id || _state[i].dev_id != dev_id_cache_value) {
  984. // restore cached value
  985. _state[i].dev_id = dev_id_cache_value;
  986. // return failure
  987. return false;
  988. }
  989. // if expected_dev_id is configured and the detected dev_id is different, return false
  990. if (_state[i].expected_dev_id != -1 && _state[i].expected_dev_id != _state[i].dev_id) {
  991. return false;
  992. }
  993. // if we got here then it must be configured
  994. return true;
  995. }
  996. bool Compass::configured(void)
  997. {
  998. bool all_configured = true;
  999. for(uint8_t i=0; i<get_count(); i++) {
  1000. all_configured = all_configured && (!use_for_yaw(i) || configured(i));
  1001. }
  1002. return all_configured;
  1003. }
  1004. // Update raw magnetometer values from HIL data
  1005. //
  1006. void Compass::setHIL(uint8_t instance, float roll, float pitch, float yaw)
  1007. {
  1008. Matrix3f R;
  1009. // create a rotation matrix for the given attitude
  1010. R.from_euler(roll, pitch, yaw);
  1011. if (!is_equal(_hil.last_declination,get_declination())) {
  1012. _setup_earth_field();
  1013. _hil.last_declination = get_declination();
  1014. }
  1015. // convert the earth frame magnetic vector to body frame, and
  1016. // apply the offsets
  1017. _hil.field[instance] = R.mul_transpose(_hil.Bearth);
  1018. // apply default board orientation for this compass type. This is
  1019. // a noop on most boards
  1020. _hil.field[instance].rotate(MAG_BOARD_ORIENTATION);
  1021. // add user selectable orientation
  1022. _hil.field[instance].rotate((enum Rotation)_state[0].orientation.get());
  1023. if (!_state[0].external) {
  1024. // and add in AHRS_ORIENTATION setting if not an external compass
  1025. if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) {
  1026. _hil.field[instance] = *_custom_rotation * _hil.field[instance];
  1027. } else {
  1028. _hil.field[instance].rotate(_board_orientation);
  1029. }
  1030. }
  1031. _hil.healthy[instance] = true;
  1032. }
  1033. // Update raw magnetometer values from HIL mag vector
  1034. //
  1035. void Compass::setHIL(uint8_t instance, const Vector3f &mag, uint32_t update_usec)
  1036. {
  1037. _hil.field[instance] = mag;
  1038. _hil.healthy[instance] = true;
  1039. _state[instance].last_update_usec = update_usec;
  1040. }
  1041. const Vector3f& Compass::getHIL(uint8_t instance) const
  1042. {
  1043. return _hil.field[instance];
  1044. }
  1045. // setup _Bearth
  1046. void Compass::_setup_earth_field(void)
  1047. {
  1048. // assume a earth field strength of 400
  1049. _hil.Bearth(400, 0, 0);
  1050. // rotate _Bearth for inclination and declination. -66 degrees
  1051. // is the inclination in Canberra, Australia
  1052. Matrix3f R;
  1053. R.from_euler(0, ToRad(66), get_declination());
  1054. _hil.Bearth = R * _hil.Bearth;
  1055. }
  1056. /*
  1057. set the type of motor compensation to use
  1058. */
  1059. void Compass::motor_compensation_type(const uint8_t comp_type)
  1060. {
  1061. if (_motor_comp_type <= AP_COMPASS_MOT_COMP_CURRENT && _motor_comp_type != (int8_t)comp_type) {
  1062. _motor_comp_type = (int8_t)comp_type;
  1063. _thr = 0; // set current throttle to zero
  1064. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  1065. set_motor_compensation(i, Vector3f(0,0,0)); // clear out invalid compensation vectors
  1066. }
  1067. }
  1068. }
  1069. bool Compass::consistent() const
  1070. {
  1071. const Vector3f &primary_mag_field = get_field();
  1072. const Vector2f primary_mag_field_xy = Vector2f(primary_mag_field.x,primary_mag_field.y);
  1073. if (primary_mag_field_xy.is_zero()) {
  1074. return false;
  1075. }
  1076. const Vector3f primary_mag_field_norm = primary_mag_field.normalized();
  1077. const Vector2f primary_mag_field_xy_norm = primary_mag_field_xy.normalized();
  1078. for (uint8_t i=0; i<get_count(); i++) {
  1079. if (!use_for_yaw(i)) {
  1080. // configured not-to-be-used
  1081. continue;
  1082. }
  1083. Vector3f mag_field = get_field(i);
  1084. Vector2f mag_field_xy = Vector2f(mag_field.x,mag_field.y);
  1085. if (mag_field_xy.is_zero()) {
  1086. return false;
  1087. }
  1088. const float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length();
  1089. mag_field.normalize();
  1090. mag_field_xy.normalize();
  1091. const float xyz_ang_diff = acosf(constrain_float(mag_field*primary_mag_field_norm,-1.0f,1.0f));
  1092. const float xy_ang_diff = acosf(constrain_float(mag_field_xy*primary_mag_field_xy_norm,-1.0f,1.0f));
  1093. // check for gross misalignment on all axes
  1094. if (xyz_ang_diff > AP_COMPASS_MAX_XYZ_ANG_DIFF) {
  1095. return false;
  1096. }
  1097. // check for an unacceptable angle difference on the xy plane
  1098. if (xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF) {
  1099. return false;
  1100. }
  1101. // check for an unacceptable length difference on the xy plane
  1102. if (xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF) {
  1103. return false;
  1104. }
  1105. }
  1106. return true;
  1107. }
  1108. // singleton instance
  1109. Compass *Compass::_singleton;
  1110. namespace AP {
  1111. Compass &compass()
  1112. {
  1113. return *Compass::get_singleton();
  1114. }
  1115. }