AP_InertialSensor.cpp 74 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078
  1. #include <assert.h>
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_HAL/I2CDevice.h>
  5. #include <AP_HAL/SPIDevice.h>
  6. #include <AP_Math/AP_Math.h>
  7. #include <AP_Notify/AP_Notify.h>
  8. #include <AP_Vehicle/AP_Vehicle.h>
  9. #include <AP_BoardConfig/AP_BoardConfig.h>
  10. #include <AP_AHRS/AP_AHRS.h>
  11. #include "AP_InertialSensor.h"
  12. #include "AP_InertialSensor_BMI160.h"
  13. #include "AP_InertialSensor_Backend.h"
  14. #include "AP_InertialSensor_HIL.h"
  15. #include "AP_InertialSensor_L3G4200D.h"
  16. #include "AP_InertialSensor_LSM9DS0.h"
  17. #include "AP_InertialSensor_LSM9DS1.h"
  18. #include "AP_InertialSensor_Invensense.h"
  19. #include "AP_InertialSensor_SITL.h"
  20. #include "AP_InertialSensor_RST.h"
  21. #include "AP_InertialSensor_BMI055.h"
  22. #include "AP_InertialSensor_BMI088.h"
  23. #include "AP_InertialSensor_Invensensev2.h"
  24. /* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop.
  25. * Output is on the debug console. */
  26. #ifdef INS_TIMING_DEBUG
  27. #include <stdio.h>
  28. #define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0)
  29. #else
  30. #define timing_printf(fmt, args...)
  31. #endif
  32. #ifndef HAL_DEFAULT_INS_FAST_SAMPLE
  33. #define HAL_DEFAULT_INS_FAST_SAMPLE 0
  34. #endif
  35. extern const AP_HAL::HAL& hal;
  36. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
  37. #define DEFAULT_GYRO_FILTER 20
  38. #define DEFAULT_ACCEL_FILTER 20
  39. #define DEFAULT_STILL_THRESH 2.5f
  40. #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
  41. #define DEFAULT_GYRO_FILTER 4
  42. #define DEFAULT_ACCEL_FILTER 10
  43. #define DEFAULT_STILL_THRESH 0.1f
  44. #else
  45. #define DEFAULT_GYRO_FILTER 20
  46. #define DEFAULT_ACCEL_FILTER 20
  47. #define DEFAULT_STILL_THRESH 0.1f
  48. #endif
  49. #define SAMPLE_UNIT 1
  50. #define GYRO_INIT_MAX_DIFF_DPS 0.1f
  51. // Class level parameters
  52. const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
  53. // 0 was PRODUCT_ID
  54. /*
  55. The following parameter indexes and reserved from previous use
  56. as accel offsets and scaling from before the 16g change in the
  57. PX4 backend:
  58. ACCSCAL : 1
  59. ACCOFFS : 2
  60. MPU6K_FILTER: 4
  61. ACC2SCAL : 5
  62. ACC2OFFS : 6
  63. ACC3SCAL : 8
  64. ACC3OFFS : 9
  65. CALSENSFRAME : 11
  66. */
  67. // @Param: GYROFFS_X
  68. // @DisplayName: Gyro offsets of X axis
  69. // @Description: Gyro sensor offsets of X axis. This is setup on each boot during gyro calibrations
  70. // @Units: rad/s
  71. // @User: Advanced
  72. // @Param: GYROFFS_Y
  73. // @DisplayName: Gyro offsets of Y axis
  74. // @Description: Gyro sensor offsets of Y axis. This is setup on each boot during gyro calibrations
  75. // @Units: rad/s
  76. // @User: Advanced
  77. // @Param: GYROFFS_Z
  78. // @DisplayName: Gyro offsets of Z axis
  79. // @Description: Gyro sensor offsets of Z axis. This is setup on each boot during gyro calibrations
  80. // @Units: rad/s
  81. // @User: Advanced
  82. AP_GROUPINFO("GYROFFS", 3, AP_InertialSensor, _gyro_offset[0], 0),
  83. // @Param: GYR2OFFS_X
  84. // @DisplayName: Gyro2 offsets of X axis
  85. // @Description: Gyro2 sensor offsets of X axis. This is setup on each boot during gyro calibrations
  86. // @Units: rad/s
  87. // @User: Advanced
  88. // @Param: GYR2OFFS_Y
  89. // @DisplayName: Gyro2 offsets of Y axis
  90. // @Description: Gyro2 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
  91. // @Units: rad/s
  92. // @User: Advanced
  93. // @Param: GYR2OFFS_Z
  94. // @DisplayName: Gyro2 offsets of Z axis
  95. // @Description: Gyro2 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
  96. // @Units: rad/s
  97. // @User: Advanced
  98. AP_GROUPINFO("GYR2OFFS", 7, AP_InertialSensor, _gyro_offset[1], 0),
  99. // @Param: GYR3OFFS_X
  100. // @DisplayName: Gyro3 offsets of X axis
  101. // @Description: Gyro3 sensor offsets of X axis. This is setup on each boot during gyro calibrations
  102. // @Units: rad/s
  103. // @User: Advanced
  104. // @Param: GYR3OFFS_Y
  105. // @DisplayName: Gyro3 offsets of Y axis
  106. // @Description: Gyro3 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
  107. // @Units: rad/s
  108. // @User: Advanced
  109. // @Param: GYR3OFFS_Z
  110. // @DisplayName: Gyro3 offsets of Z axis
  111. // @Description: Gyro3 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
  112. // @Units: rad/s
  113. // @User: Advanced
  114. AP_GROUPINFO("GYR3OFFS", 10, AP_InertialSensor, _gyro_offset[2], 0),
  115. // @Param: ACCSCAL_X
  116. // @DisplayName: Accelerometer scaling of X axis
  117. // @Description: Accelerometer scaling of X axis. Calculated during acceleration calibration routine
  118. // @Range: 0.8 1.2
  119. // @User: Advanced
  120. // @Param: ACCSCAL_Y
  121. // @DisplayName: Accelerometer scaling of Y axis
  122. // @Description: Accelerometer scaling of Y axis Calculated during acceleration calibration routine
  123. // @Range: 0.8 1.2
  124. // @User: Advanced
  125. // @Param: ACCSCAL_Z
  126. // @DisplayName: Accelerometer scaling of Z axis
  127. // @Description: Accelerometer scaling of Z axis Calculated during acceleration calibration routine
  128. // @Range: 0.8 1.2
  129. // @User: Advanced
  130. AP_GROUPINFO("ACCSCAL", 12, AP_InertialSensor, _accel_scale[0], 0),
  131. // @Param: ACCOFFS_X
  132. // @DisplayName: Accelerometer offsets of X axis
  133. // @Description: Accelerometer offsets of X axis. This is setup using the acceleration calibration or level operations
  134. // @Units: m/s/s
  135. // @Range: -3.5 3.5
  136. // @User: Advanced
  137. // @Param: ACCOFFS_Y
  138. // @DisplayName: Accelerometer offsets of Y axis
  139. // @Description: Accelerometer offsets of Y axis. This is setup using the acceleration calibration or level operations
  140. // @Units: m/s/s
  141. // @Range: -3.5 3.5
  142. // @User: Advanced
  143. // @Param: ACCOFFS_Z
  144. // @DisplayName: Accelerometer offsets of Z axis
  145. // @Description: Accelerometer offsets of Z axis. This is setup using the acceleration calibration or level operations
  146. // @Units: m/s/s
  147. // @Range: -3.5 3.5
  148. // @User: Advanced
  149. AP_GROUPINFO("ACCOFFS", 13, AP_InertialSensor, _accel_offset[0], 0),
  150. // @Param: ACC2SCAL_X
  151. // @DisplayName: Accelerometer2 scaling of X axis
  152. // @Description: Accelerometer2 scaling of X axis. Calculated during acceleration calibration routine
  153. // @Range: 0.8 1.2
  154. // @User: Advanced
  155. // @Param: ACC2SCAL_Y
  156. // @DisplayName: Accelerometer2 scaling of Y axis
  157. // @Description: Accelerometer2 scaling of Y axis Calculated during acceleration calibration routine
  158. // @Range: 0.8 1.2
  159. // @User: Advanced
  160. // @Param: ACC2SCAL_Z
  161. // @DisplayName: Accelerometer2 scaling of Z axis
  162. // @Description: Accelerometer2 scaling of Z axis Calculated during acceleration calibration routine
  163. // @Range: 0.8 1.2
  164. // @User: Advanced
  165. AP_GROUPINFO("ACC2SCAL", 14, AP_InertialSensor, _accel_scale[1], 0),
  166. // @Param: ACC2OFFS_X
  167. // @DisplayName: Accelerometer2 offsets of X axis
  168. // @Description: Accelerometer2 offsets of X axis. This is setup using the acceleration calibration or level operations
  169. // @Units: m/s/s
  170. // @Range: -3.5 3.5
  171. // @User: Advanced
  172. // @Param: ACC2OFFS_Y
  173. // @DisplayName: Accelerometer2 offsets of Y axis
  174. // @Description: Accelerometer2 offsets of Y axis. This is setup using the acceleration calibration or level operations
  175. // @Units: m/s/s
  176. // @Range: -3.5 3.5
  177. // @User: Advanced
  178. // @Param: ACC2OFFS_Z
  179. // @DisplayName: Accelerometer2 offsets of Z axis
  180. // @Description: Accelerometer2 offsets of Z axis. This is setup using the acceleration calibration or level operations
  181. // @Units: m/s/s
  182. // @Range: -3.5 3.5
  183. // @User: Advanced
  184. AP_GROUPINFO("ACC2OFFS", 15, AP_InertialSensor, _accel_offset[1], 0),
  185. // @Param: ACC3SCAL_X
  186. // @DisplayName: Accelerometer3 scaling of X axis
  187. // @Description: Accelerometer3 scaling of X axis. Calculated during acceleration calibration routine
  188. // @Range: 0.8 1.2
  189. // @User: Advanced
  190. // @Param: ACC3SCAL_Y
  191. // @DisplayName: Accelerometer3 scaling of Y axis
  192. // @Description: Accelerometer3 scaling of Y axis Calculated during acceleration calibration routine
  193. // @Range: 0.8 1.2
  194. // @User: Advanced
  195. // @Param: ACC3SCAL_Z
  196. // @DisplayName: Accelerometer3 scaling of Z axis
  197. // @Description: Accelerometer3 scaling of Z axis Calculated during acceleration calibration routine
  198. // @Range: 0.8 1.2
  199. // @User: Advanced
  200. AP_GROUPINFO("ACC3SCAL", 16, AP_InertialSensor, _accel_scale[2], 0),
  201. // @Param: ACC3OFFS_X
  202. // @DisplayName: Accelerometer3 offsets of X axis
  203. // @Description: Accelerometer3 offsets of X axis. This is setup using the acceleration calibration or level operations
  204. // @Units: m/s/s
  205. // @Range: -3.5 3.5
  206. // @User: Advanced
  207. // @Param: ACC3OFFS_Y
  208. // @DisplayName: Accelerometer3 offsets of Y axis
  209. // @Description: Accelerometer3 offsets of Y axis. This is setup using the acceleration calibration or level operations
  210. // @Units: m/s/s
  211. // @Range: -3.5 3.5
  212. // @User: Advanced
  213. // @Param: ACC3OFFS_Z
  214. // @DisplayName: Accelerometer3 offsets of Z axis
  215. // @Description: Accelerometer3 offsets of Z axis. This is setup using the acceleration calibration or level operations
  216. // @Units: m/s/s
  217. // @Range: -3.5 3.5
  218. // @User: Advanced
  219. AP_GROUPINFO("ACC3OFFS", 17, AP_InertialSensor, _accel_offset[2], 0),
  220. // @Param: GYRO_FILTER
  221. // @DisplayName: Gyro filter cutoff frequency
  222. // @Description: Filter cutoff frequency for gyroscopes. This can be set to a lower value to try to cope with very high vibration levels in aircraft. A value of zero means no filtering (not recommended!)
  223. // @Units: Hz
  224. // @Range: 0 256
  225. // @User: Advanced
  226. AP_GROUPINFO("GYRO_FILTER", 18, AP_InertialSensor, _gyro_filter_cutoff, DEFAULT_GYRO_FILTER),
  227. // @Param: ACCEL_FILTER
  228. // @DisplayName: Accel filter cutoff frequency
  229. // @Description: Filter cutoff frequency for accelerometers. This can be set to a lower value to try to cope with very high vibration levels in aircraft. A value of zero means no filtering (not recommended!)
  230. // @Units: Hz
  231. // @Range: 0 256
  232. // @User: Advanced
  233. AP_GROUPINFO("ACCEL_FILTER", 19, AP_InertialSensor, _accel_filter_cutoff, DEFAULT_ACCEL_FILTER),
  234. // @Param: USE
  235. // @DisplayName: Use first IMU for attitude, velocity and position estimates
  236. // @Description: Use first IMU for attitude, velocity and position estimates
  237. // @Values: 0:Disabled,1:Enabled
  238. // @User: Advanced
  239. AP_GROUPINFO("USE", 20, AP_InertialSensor, _use[0], 1),
  240. // @Param: USE2
  241. // @DisplayName: Use second IMU for attitude, velocity and position estimates
  242. // @Description: Use second IMU for attitude, velocity and position estimates
  243. // @Values: 0:Disabled,1:Enabled
  244. // @User: Advanced
  245. AP_GROUPINFO("USE2", 21, AP_InertialSensor, _use[1], 1),
  246. // @Param: USE3
  247. // @DisplayName: Use third IMU for attitude, velocity and position estimates
  248. // @Description: Use third IMU for attitude, velocity and position estimates
  249. // @Values: 0:Disabled,1:Enabled
  250. // @User: Advanced
  251. AP_GROUPINFO("USE3", 22, AP_InertialSensor, _use[2], 1),
  252. // @Param: STILL_THRESH
  253. // @DisplayName: Stillness threshold for detecting if we are moving
  254. // @Description: Threshold to tolerate vibration to determine if vehicle is motionless. This depends on the frame type and if there is a constant vibration due to motors before launch or after landing. Total motionless is about 0.05. Suggested values: Planes/rover use 0.1, multirotors use 1, tradHeli uses 5
  255. // @Range: 0.05 50
  256. // @User: Advanced
  257. AP_GROUPINFO("STILL_THRESH", 23, AP_InertialSensor, _still_threshold, DEFAULT_STILL_THRESH),
  258. // @Param: GYR_CAL
  259. // @DisplayName: Gyro Calibration scheme
  260. // @Description: Conrols when automatic gyro calibration is performed
  261. // @Values: 0:Never, 1:Start-up only
  262. // @User: Advanced
  263. AP_GROUPINFO("GYR_CAL", 24, AP_InertialSensor, _gyro_cal_timing, 1),
  264. // @Param: TRIM_OPTION
  265. // @DisplayName: Accel cal trim option
  266. // @Description: Specifies how the accel cal routine determines the trims
  267. // @User: Advanced
  268. // @Values: 0:Don't adjust the trims,1:Assume first orientation was level,2:Assume ACC_BODYFIX is perfectly aligned to the vehicle
  269. AP_GROUPINFO("TRIM_OPTION", 25, AP_InertialSensor, _trim_option, 1),
  270. // @Param: ACC_BODYFIX
  271. // @DisplayName: Body-fixed accelerometer
  272. // @Description: The body-fixed accelerometer to be used for trim calculation
  273. // @User: Advanced
  274. // @Values: 1:IMU 1,2:IMU 2,3:IMU 3
  275. AP_GROUPINFO("ACC_BODYFIX", 26, AP_InertialSensor, _acc_body_aligned, 2),
  276. // @Param: POS1_X
  277. // @DisplayName: IMU accelerometer X position
  278. // @Description: X position of the first IMU Accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  279. // @Units: m
  280. // @Range: -10 10
  281. // @User: Advanced
  282. // @Param: POS1_Y
  283. // @DisplayName: IMU accelerometer Y position
  284. // @Description: Y position of the first IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  285. // @Units: m
  286. // @Range: -10 10
  287. // @User: Advanced
  288. // @Param: POS1_Z
  289. // @DisplayName: IMU accelerometer Z position
  290. // @Description: Z position of the first IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  291. // @Units: m
  292. // @Range: -10 10
  293. // @User: Advanced
  294. AP_GROUPINFO("POS1", 27, AP_InertialSensor, _accel_pos[0], 0.0f),
  295. // @Param: POS2_X
  296. // @DisplayName: IMU accelerometer X position
  297. // @Description: X position of the second IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  298. // @Units: m
  299. // @Range: -10 10
  300. // @User: Advanced
  301. // @Param: POS2_Y
  302. // @DisplayName: IMU accelerometer Y position
  303. // @Description: Y position of the second IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  304. // @Units: m
  305. // @Range: -10 10
  306. // @User: Advanced
  307. // @Param: POS2_Z
  308. // @DisplayName: IMU accelerometer Z position
  309. // @Description: Z position of the second IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  310. // @Units: m
  311. // @Range: -10 10
  312. // @User: Advanced
  313. AP_GROUPINFO("POS2", 28, AP_InertialSensor, _accel_pos[1], 0.0f),
  314. // @Param: POS3_X
  315. // @DisplayName: IMU accelerometer X position
  316. // @Description: X position of the third IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  317. // @Units: m
  318. // @Range: -10 10
  319. // @User: Advanced
  320. // @Param: POS3_Y
  321. // @DisplayName: IMU accelerometer Y position
  322. // @Description: Y position of the third IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  323. // @Units: m
  324. // @Range: -10 10
  325. // @User: Advanced
  326. // @Param: POS3_Z
  327. // @DisplayName: IMU accelerometer Z position
  328. // @Description: Z position of the third IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
  329. // @Units: m
  330. // @Range: -10 10
  331. // @User: Advanced
  332. AP_GROUPINFO("POS3", 29, AP_InertialSensor, _accel_pos[2], 0.0f),
  333. // @Param: GYR_ID
  334. // @DisplayName: Gyro ID
  335. // @Description: Gyro sensor ID, taking into account its type, bus and instance
  336. // @ReadOnly: True
  337. // @User: Advanced
  338. AP_GROUPINFO("GYR_ID", 30, AP_InertialSensor, _gyro_id[0], 0),
  339. // @Param: GYR2_ID
  340. // @DisplayName: Gyro2 ID
  341. // @Description: Gyro2 sensor ID, taking into account its type, bus and instance
  342. // @ReadOnly: True
  343. // @User: Advanced
  344. AP_GROUPINFO("GYR2_ID", 31, AP_InertialSensor, _gyro_id[1], 0),
  345. // @Param: GYR3_ID
  346. // @DisplayName: Gyro3 ID
  347. // @Description: Gyro3 sensor ID, taking into account its type, bus and instance
  348. // @ReadOnly: True
  349. // @User: Advanced
  350. AP_GROUPINFO("GYR3_ID", 32, AP_InertialSensor, _gyro_id[2], 0),
  351. // @Param: ACC_ID
  352. // @DisplayName: Accelerometer ID
  353. // @Description: Accelerometer sensor ID, taking into account its type, bus and instance
  354. // @ReadOnly: True
  355. // @User: Advanced
  356. AP_GROUPINFO("ACC_ID", 33, AP_InertialSensor, _accel_id[0], 0),
  357. // @Param: ACC2_ID
  358. // @DisplayName: Accelerometer2 ID
  359. // @Description: Accelerometer2 sensor ID, taking into account its type, bus and instance
  360. // @ReadOnly: True
  361. // @User: Advanced
  362. AP_GROUPINFO("ACC2_ID", 34, AP_InertialSensor, _accel_id[1], 0),
  363. // @Param: ACC3_ID
  364. // @DisplayName: Accelerometer3 ID
  365. // @Description: Accelerometer3 sensor ID, taking into account its type, bus and instance
  366. // @ReadOnly: True
  367. // @User: Advanced
  368. AP_GROUPINFO("ACC3_ID", 35, AP_InertialSensor, _accel_id[2], 0),
  369. // @Param: FAST_SAMPLE
  370. // @DisplayName: Fast sampling mask
  371. // @Description: Mask of IMUs to enable fast sampling on, if available
  372. // @User: Advanced
  373. // @Values: 1:FirstIMUOnly,3:FirstAndSecondIMU
  374. // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU
  375. AP_GROUPINFO("FAST_SAMPLE", 36, AP_InertialSensor, _fast_sampling_mask, HAL_DEFAULT_INS_FAST_SAMPLE),
  376. // @Group: NOTCH_
  377. // @Path: ../Filter/NotchFilter.cpp
  378. AP_SUBGROUPINFO(_notch_filter, "NOTCH_", 37, AP_InertialSensor, NotchFilterParams),
  379. // @Group: LOG_
  380. // @Path: ../AP_InertialSensor/BatchSampler.cpp
  381. AP_SUBGROUPINFO(batchsampler, "LOG_", 39, AP_InertialSensor, AP_InertialSensor::BatchSampler),
  382. // @Param: ENABLE_MASK
  383. // @DisplayName: IMU enable mask
  384. // @Description: Bitmask of IMUs to enable. It can be used to prevent startup of specific detected IMUs
  385. // @User: Advanced
  386. // @Values: 1:FirstIMUOnly,3:FirstAndSecondIMU,7:FirstSecondAndThirdIMU,127:AllIMUs
  387. // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU
  388. AP_GROUPINFO("ENABLE_MASK", 40, AP_InertialSensor, _enable_mask, 0x7F),
  389. // @Group: HNTCH_
  390. // @Path: ../Filter/HarmonicNotchFilter.cpp
  391. AP_SUBGROUPINFO(_harmonic_notch_filter, "HNTCH_", 41, AP_InertialSensor, HarmonicNotchFilterParams),
  392. /*
  393. NOTE: parameter indexes have gaps above. When adding new
  394. parameters check for conflicts carefully
  395. */
  396. AP_GROUPEND
  397. };
  398. AP_InertialSensor *AP_InertialSensor::_singleton = nullptr;
  399. AP_InertialSensor::AP_InertialSensor() :
  400. _board_orientation(ROTATION_NONE),
  401. _log_raw_bit(-1)
  402. {
  403. if (_singleton) {
  404. AP_HAL::panic("Too many inertial sensors");
  405. }
  406. _singleton = this;
  407. AP_Param::setup_object_defaults(this, var_info);
  408. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  409. _gyro_cal_ok[i] = true;
  410. _accel_max_abs_offsets[i] = 3.5f;
  411. }
  412. for (uint8_t i=0; i<INS_VIBRATION_CHECK_INSTANCES; i++) {
  413. _accel_vibe_floor_filter[i].set_cutoff_frequency(AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ);
  414. _accel_vibe_filter[i].set_cutoff_frequency(AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ);
  415. }
  416. AP_AccelCal::register_client(this);
  417. }
  418. /*
  419. * Get the AP_InertialSensor singleton
  420. */
  421. AP_InertialSensor *AP_InertialSensor::get_singleton()
  422. {
  423. if (!_singleton) {
  424. _singleton = new AP_InertialSensor();
  425. }
  426. return _singleton;
  427. }
  428. /*
  429. register a new gyro instance
  430. */
  431. uint8_t AP_InertialSensor::register_gyro(uint16_t raw_sample_rate_hz,
  432. uint32_t id)
  433. {
  434. if (_gyro_count == INS_MAX_INSTANCES) {
  435. AP_HAL::panic("Too many gyros");
  436. }
  437. _gyro_raw_sample_rates[_gyro_count] = raw_sample_rate_hz;
  438. _gyro_over_sampling[_gyro_count] = 1;
  439. _gyro_raw_sampling_multiplier[_gyro_count] = INT16_MAX/radians(2000);
  440. bool saved = _gyro_id[_gyro_count].load();
  441. if (saved && (uint32_t)_gyro_id[_gyro_count] != id) {
  442. // inconsistent gyro id - mark it as needing calibration
  443. _gyro_cal_ok[_gyro_count] = false;
  444. }
  445. _gyro_id[_gyro_count].set((int32_t) id);
  446. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  447. if (!saved) {
  448. // assume this is the same sensor and save its ID to allow seamless
  449. // transition from when we didn't have the IDs.
  450. _gyro_id[_gyro_count].save();
  451. }
  452. #endif
  453. return _gyro_count++;
  454. }
  455. /*
  456. register a new accel instance
  457. */
  458. uint8_t AP_InertialSensor::register_accel(uint16_t raw_sample_rate_hz,
  459. uint32_t id)
  460. {
  461. if (_accel_count == INS_MAX_INSTANCES) {
  462. AP_HAL::panic("Too many accels");
  463. }
  464. _accel_raw_sample_rates[_accel_count] = raw_sample_rate_hz;
  465. _accel_over_sampling[_accel_count] = 1;
  466. _accel_raw_sampling_multiplier[_accel_count] = INT16_MAX/(16*GRAVITY_MSS);
  467. bool saved = _accel_id[_accel_count].load();
  468. if (!saved) {
  469. // inconsistent accel id
  470. _accel_id_ok[_accel_count] = false;
  471. } else if ((uint32_t)_accel_id[_accel_count] != id) {
  472. // inconsistent accel id
  473. _accel_id_ok[_accel_count] = false;
  474. } else {
  475. _accel_id_ok[_accel_count] = true;
  476. }
  477. _accel_id[_accel_count].set((int32_t) id);
  478. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  479. // assume this is the same sensor and save its ID to allow seamless
  480. // transition from when we didn't have the IDs.
  481. _accel_id_ok[_accel_count] = true;
  482. _accel_id[_accel_count].save();
  483. #endif
  484. return _accel_count++;
  485. }
  486. /*
  487. * Start all backends for gyro and accel measurements. It automatically calls
  488. * detect_backends() if it has not been called already.
  489. */
  490. void AP_InertialSensor::_start_backends()
  491. {
  492. detect_backends();
  493. for (uint8_t i = 0; i < _backend_count; i++) {
  494. _backends[i]->start();
  495. }
  496. if (_gyro_count == 0 || _accel_count == 0) {
  497. AP_HAL::panic("INS needs at least 1 gyro and 1 accel");
  498. }
  499. // clear IDs for unused sensor instances
  500. for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
  501. _accel_id[i].set(0);
  502. }
  503. for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
  504. _gyro_id[i].set(0);
  505. }
  506. }
  507. /* Find the N instance of the backend that has already been successfully detected */
  508. AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id, uint8_t instance)
  509. {
  510. assert(_backends_detected);
  511. uint8_t found = 0;
  512. for (uint8_t i = 0; i < _backend_count; i++) {
  513. int16_t id = _backends[i]->get_id();
  514. if (id < 0 || id != backend_id) {
  515. continue;
  516. }
  517. if (instance == found) {
  518. return _backends[i];
  519. } else {
  520. found++;
  521. }
  522. }
  523. return nullptr;
  524. }
  525. void
  526. AP_InertialSensor::init(uint16_t sample_rate)
  527. {
  528. // remember the sample rate
  529. _sample_rate = sample_rate;
  530. _loop_delta_t = 1.0f / sample_rate;
  531. // we don't allow deltat values greater than 10x the normal loop
  532. // time to be exposed outside of INS. Large deltat values can
  533. // cause divergence of state estimators
  534. _loop_delta_t_max = 10 * _loop_delta_t;
  535. if (_gyro_count == 0 && _accel_count == 0) {
  536. _start_backends();
  537. }
  538. // initialise accel scale if need be. This is needed as we can't
  539. // give non-zero default values for vectors in AP_Param
  540. for (uint8_t i=0; i<get_accel_count(); i++) {
  541. if (_accel_scale[i].get().is_zero()) {
  542. _accel_scale[i].set(Vector3f(1,1,1));
  543. }
  544. }
  545. // calibrate gyros unless gyro calibration has been disabled
  546. if (gyro_calibration_timing() != GYRO_CAL_NEVER) {
  547. init_gyro();
  548. }
  549. _sample_period_usec = 1000*1000UL / _sample_rate;
  550. // establish the baseline time between samples
  551. _delta_time = 0;
  552. _next_sample_usec = 0;
  553. _last_sample_usec = 0;
  554. _have_sample = false;
  555. // initialise IMU batch logging
  556. batchsampler.init();
  557. // the center frequency of the harmonic notch is always taken from the calculated value so that it can be updated
  558. // dynamically, the calculated value is always some multiple of the configured center frequency, so start with the
  559. // configured value
  560. _calculated_harmonic_notch_freq_hz = _harmonic_notch_filter.center_freq_hz();
  561. for (uint8_t i=0; i<get_gyro_count(); i++) {
  562. _gyro_harmonic_notch_filter[i].allocate_filters(_harmonic_notch_filter.harmonics());
  563. // initialise default settings, these will be subsequently changed in AP_InertialSensor_Backend::update_gyro()
  564. _gyro_harmonic_notch_filter[i].init(_gyro_raw_sample_rates[i], _calculated_harmonic_notch_freq_hz,
  565. _harmonic_notch_filter.bandwidth_hz(), _harmonic_notch_filter.attenuation_dB());
  566. }
  567. }
  568. bool AP_InertialSensor::_add_backend(AP_InertialSensor_Backend *backend)
  569. {
  570. if (!backend) {
  571. return false;
  572. }
  573. if (_backend_count == INS_MAX_BACKENDS) {
  574. AP_HAL::panic("Too many INS backends");
  575. }
  576. _backends[_backend_count++] = backend;
  577. return true;
  578. }
  579. /*
  580. detect available backends for this board
  581. */
  582. void
  583. AP_InertialSensor::detect_backends(void)
  584. {
  585. if (_backends_detected) {
  586. return;
  587. }
  588. _backends_detected = true;
  589. #if defined(HAL_CHIBIOS_ARCH_CUBEBLACK)
  590. // special case for CubeBlack, where the IMUs on the isolated
  591. // board could fail on some boards. If the user has INS_USE=1,
  592. // INS_USE2=1 and INS_USE3=0 then force INS_USE3 to 1. This is
  593. // done as users loading past parameter files may end up with
  594. // INS_USE3=0 unintentionally, which is unsafe on these
  595. // boards. For users who really want limited IMUs they will need
  596. // to either use the INS_ENABLE_MASK or set INS_USE2=0 which will
  597. // enable the first IMU without triggering this check
  598. if (_use[0] == 1 && _use[1] == 1 && _use[2] == 0) {
  599. _use[2].set(1);
  600. }
  601. #endif
  602. uint8_t probe_count = 0;
  603. uint8_t enable_mask = uint8_t(_enable_mask.get());
  604. uint8_t found_mask = 0;
  605. /*
  606. use ADD_BACKEND() macro to allow for INS_ENABLE_MASK for enabling/disabling INS backends
  607. */
  608. #define ADD_BACKEND(x) do { \
  609. if (((1U<<probe_count)&enable_mask) && _add_backend(x)) { \
  610. found_mask |= (1U<<probe_count); \
  611. } \
  612. probe_count++; \
  613. } while (0)
  614. // macro for use by HAL_INS_PROBE_LIST
  615. #define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address)
  616. if (_hil_mode) {
  617. ADD_BACKEND(AP_InertialSensor_HIL::detect(*this));
  618. return;
  619. }
  620. #if defined(HAL_INS_PROBE_LIST)
  621. // IMUs defined by IMU lines in hwdef.dat
  622. HAL_INS_PROBE_LIST;
  623. #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
  624. ADD_BACKEND(AP_InertialSensor_SITL::detect(*this));
  625. #elif HAL_INS_DEFAULT == HAL_INS_HIL
  626. ADD_BACKEND(AP_InertialSensor_HIL::detect(*this));
  627. #elif AP_FEATURE_BOARD_DETECT
  628. switch (AP_BoardConfig::get_board_type()) {
  629. case AP_BoardConfig::PX4_BOARD_PX4V1:
  630. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_NONE));
  631. break;
  632. case AP_BoardConfig::PX4_BOARD_PIXHAWK:
  633. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_ROLL_180));
  634. ADD_BACKEND(AP_InertialSensor_LSM9DS0::probe(*this,
  635. hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
  636. hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME),
  637. ROTATION_ROLL_180,
  638. ROTATION_ROLL_180_YAW_270,
  639. ROTATION_PITCH_180));
  640. break;
  641. case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
  642. // older Pixhawk2 boards have the MPU6000 instead of MPU9250
  643. _fast_sampling_mask.set_default(1);
  644. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_PITCH_180));
  645. ADD_BACKEND(AP_InertialSensor_LSM9DS0::probe(*this,
  646. hal.spi->get_device(HAL_INS_LSM9DS0_EXT_G_NAME),
  647. hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME),
  648. ROTATION_ROLL_180_YAW_270,
  649. ROTATION_ROLL_180_YAW_90,
  650. ROTATION_ROLL_180_YAW_90));
  651. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270));
  652. // new cubes have ICM20602, ICM20948, ICM20649
  653. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20602_ext"), ROTATION_ROLL_180_YAW_270));
  654. ADD_BACKEND(AP_InertialSensor_Invensensev2::probe(*this, hal.spi->get_device("icm20948_ext"), ROTATION_PITCH_180));
  655. ADD_BACKEND(AP_InertialSensor_Invensensev2::probe(*this, hal.spi->get_device("icm20948"), ROTATION_YAW_270));
  656. break;
  657. case AP_BoardConfig::PX4_BOARD_FMUV5:
  658. case AP_BoardConfig::PX4_BOARD_FMUV6:
  659. _fast_sampling_mask.set_default(1);
  660. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20689"), ROTATION_NONE));
  661. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20602"), ROTATION_NONE));
  662. // allow for either BMI055 or BMI088
  663. ADD_BACKEND(AP_InertialSensor_BMI055::probe(*this,
  664. hal.spi->get_device("bmi055_a"),
  665. hal.spi->get_device("bmi055_g"),
  666. ROTATION_ROLL_180_YAW_90));
  667. ADD_BACKEND(AP_InertialSensor_BMI088::probe(*this,
  668. hal.spi->get_device("bmi055_a"),
  669. hal.spi->get_device("bmi055_g"),
  670. ROTATION_ROLL_180_YAW_90));
  671. break;
  672. case AP_BoardConfig::PX4_BOARD_SP01:
  673. _fast_sampling_mask.set_default(1);
  674. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_NONE));
  675. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_NONE));
  676. break;
  677. case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
  678. _fast_sampling_mask.set_default(3);
  679. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_NAME), ROTATION_ROLL_180_YAW_90));
  680. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90));
  681. break;
  682. case AP_BoardConfig::PX4_BOARD_PHMINI:
  683. // PHMINI uses ICM20608 on the ACCEL_MAG device and a MPU9250 on the old MPU6000 CS line
  684. _fast_sampling_mask.set_default(3);
  685. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_AM_NAME), ROTATION_ROLL_180));
  686. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180));
  687. break;
  688. case AP_BoardConfig::PX4_BOARD_AUAV21:
  689. // AUAV2.1 uses ICM20608 on the ACCEL_MAG device and a MPU9250 on the old MPU6000 CS line
  690. _fast_sampling_mask.set_default(3);
  691. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_AM_NAME), ROTATION_ROLL_180_YAW_90));
  692. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90));
  693. break;
  694. case AP_BoardConfig::PX4_BOARD_PH2SLIM:
  695. _fast_sampling_mask.set_default(1);
  696. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270));
  697. break;
  698. case AP_BoardConfig::PX4_BOARD_AEROFC:
  699. _fast_sampling_mask.set_default(1);
  700. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU6500_NAME), ROTATION_YAW_270));
  701. break;
  702. case AP_BoardConfig::PX4_BOARD_MINDPXV2:
  703. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU6500_NAME), ROTATION_NONE));
  704. ADD_BACKEND(AP_InertialSensor_LSM9DS0::probe(*this,
  705. hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
  706. hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME),
  707. ROTATION_YAW_90,
  708. ROTATION_YAW_90,
  709. ROTATION_YAW_90));
  710. break;
  711. case AP_BoardConfig::VRX_BOARD_BRAIN54:
  712. _fast_sampling_mask.set_default(7);
  713. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_YAW_180));
  714. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_EXT_NAME), ROTATION_YAW_180));
  715. #ifdef HAL_INS_MPU60x0_IMU_NAME
  716. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_IMU_NAME), ROTATION_YAW_180));
  717. #endif
  718. break;
  719. case AP_BoardConfig::VRX_BOARD_BRAIN51:
  720. case AP_BoardConfig::VRX_BOARD_BRAIN52:
  721. case AP_BoardConfig::VRX_BOARD_BRAIN52E:
  722. case AP_BoardConfig::VRX_BOARD_CORE10:
  723. case AP_BoardConfig::VRX_BOARD_UBRAIN51:
  724. case AP_BoardConfig::VRX_BOARD_UBRAIN52:
  725. ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_YAW_180));
  726. break;
  727. case AP_BoardConfig::PX4_BOARD_PCNC1:
  728. _add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_ROLL_180));
  729. break;
  730. default:
  731. break;
  732. }
  733. #elif HAL_INS_DEFAULT == HAL_INS_NONE
  734. // no INS device
  735. #else
  736. #error Unrecognised HAL_INS_TYPE setting
  737. #endif
  738. if (_backend_count == 0) {
  739. AP_BoardConfig::sensor_config_error("INS: unable to initialise driver");
  740. }
  741. }
  742. // Armed, Copter, PixHawk:
  743. // ins_periodic: 57500 events, 0 overruns, 208754us elapsed, 3us avg, min 1us max 218us 40.662us rms
  744. void AP_InertialSensor::periodic()
  745. {
  746. batchsampler.periodic();
  747. }
  748. /*
  749. _calculate_trim - calculates the x and y trim angles. The
  750. accel_sample must be correctly scaled, offset and oriented for the
  751. board
  752. */
  753. bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch)
  754. {
  755. trim_pitch = atan2f(accel_sample.x, norm(accel_sample.y, accel_sample.z));
  756. trim_roll = atan2f(-accel_sample.y, -accel_sample.z);
  757. if (fabsf(trim_roll) > radians(10) ||
  758. fabsf(trim_pitch) > radians(10)) {
  759. hal.console->printf("trim over maximum of 10 degrees\n");
  760. return false;
  761. }
  762. hal.console->printf("Trim OK: roll=%.2f pitch=%.2f\n",
  763. (double)degrees(trim_roll),
  764. (double)degrees(trim_pitch));
  765. return true;
  766. }
  767. void
  768. AP_InertialSensor::init_gyro()
  769. {
  770. _init_gyro();
  771. // save calibration
  772. _save_gyro_calibration();
  773. }
  774. // accelerometer clipping reporting
  775. uint32_t AP_InertialSensor::get_accel_clip_count(uint8_t instance) const
  776. {
  777. if (instance >= get_accel_count()) {
  778. return 0;
  779. }
  780. return _accel_clip_count[instance];
  781. }
  782. // get_gyro_health_all - return true if all gyros are healthy
  783. bool AP_InertialSensor::get_gyro_health_all(void) const
  784. {
  785. for (uint8_t i=0; i<get_gyro_count(); i++) {
  786. if (!get_gyro_health(i)) {
  787. return false;
  788. }
  789. }
  790. // return true if we have at least one gyro
  791. return (get_gyro_count() > 0);
  792. }
  793. // gyro_calibration_ok_all - returns true if all gyros were calibrated successfully
  794. bool AP_InertialSensor::gyro_calibrated_ok_all() const
  795. {
  796. for (uint8_t i=0; i<get_gyro_count(); i++) {
  797. if (!gyro_calibrated_ok(i)) {
  798. return false;
  799. }
  800. }
  801. for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
  802. if (_gyro_id[i] != 0) {
  803. // missing gyro
  804. return false;
  805. }
  806. }
  807. return (get_gyro_count() > 0);
  808. }
  809. // return true if gyro instance should be used (must be healthy and have it's use parameter set to 1)
  810. bool AP_InertialSensor::use_gyro(uint8_t instance) const
  811. {
  812. if (instance >= INS_MAX_INSTANCES) {
  813. return false;
  814. }
  815. return (get_gyro_health(instance) && _use[instance]);
  816. }
  817. // get_accel_health_all - return true if all accels are healthy
  818. bool AP_InertialSensor::get_accel_health_all(void) const
  819. {
  820. for (uint8_t i=0; i<get_accel_count(); i++) {
  821. if (!get_accel_health(i)) {
  822. return false;
  823. }
  824. }
  825. // return true if we have at least one accel
  826. return (get_accel_count() > 0);
  827. }
  828. /*
  829. calculate the trim_roll and trim_pitch. This is used for redoing the
  830. trim without needing a full accel cal
  831. */
  832. bool AP_InertialSensor::calibrate_trim(float &trim_roll, float &trim_pitch)
  833. {
  834. Vector3f level_sample;
  835. // exit immediately if calibration is already in progress
  836. if (_calibrating) {
  837. return false;
  838. }
  839. _calibrating = true;
  840. const uint8_t update_dt_milliseconds = (uint8_t)(1000.0f/get_sample_rate()+0.5f);
  841. // wait 100ms for ins filter to rise
  842. for (uint8_t k=0; k<100/update_dt_milliseconds; k++) {
  843. wait_for_sample();
  844. update();
  845. hal.scheduler->delay(update_dt_milliseconds);
  846. }
  847. uint32_t num_samples = 0;
  848. while (num_samples < 400/update_dt_milliseconds) {
  849. wait_for_sample();
  850. // read samples from ins
  851. update();
  852. // capture sample
  853. Vector3f samp;
  854. samp = get_accel(0);
  855. level_sample += samp;
  856. if (!get_accel_health(0)) {
  857. goto failed;
  858. }
  859. hal.scheduler->delay(update_dt_milliseconds);
  860. num_samples++;
  861. }
  862. level_sample /= num_samples;
  863. if (!_calculate_trim(level_sample, trim_roll, trim_pitch)) {
  864. goto failed;
  865. }
  866. _calibrating = false;
  867. return true;
  868. failed:
  869. _calibrating = false;
  870. return false;
  871. }
  872. /*
  873. check if the accelerometers are calibrated in 3D and that current number of accels matched number when calibrated
  874. */
  875. bool AP_InertialSensor::accel_calibrated_ok_all() const
  876. {
  877. // calibration is not applicable for HIL mode
  878. if (_hil_mode) {
  879. return true;
  880. }
  881. // check each accelerometer has offsets saved
  882. for (uint8_t i=0; i<get_accel_count(); i++) {
  883. if (!_accel_id_ok[i]) {
  884. return false;
  885. }
  886. // exactly 0.0 offset is extremely unlikely
  887. if (_accel_offset[i].get().is_zero()) {
  888. return false;
  889. }
  890. // zero scaling also indicates not calibrated
  891. if (_accel_scale[i].get().is_zero()) {
  892. return false;
  893. }
  894. }
  895. for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
  896. if (_accel_id[i] != 0) {
  897. // missing accel
  898. return false;
  899. }
  900. }
  901. // check calibrated accels matches number of accels (no unused accels should have offsets or scaling)
  902. if (get_accel_count() < INS_MAX_INSTANCES) {
  903. for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
  904. const Vector3f &scaling = _accel_scale[i].get();
  905. bool have_scaling = (!is_zero(scaling.x) && !is_equal(scaling.x,1.0f)) || (!is_zero(scaling.y) && !is_equal(scaling.y,1.0f)) || (!is_zero(scaling.z) && !is_equal(scaling.z,1.0f));
  906. bool have_offsets = !_accel_offset[i].get().is_zero();
  907. if (have_scaling || have_offsets) {
  908. return false;
  909. }
  910. }
  911. }
  912. // if we got this far the accelerometers must have been calibrated
  913. return true;
  914. }
  915. // return true if accel instance should be used (must be healthy and have it's use parameter set to 1)
  916. bool AP_InertialSensor::use_accel(uint8_t instance) const
  917. {
  918. if (instance >= INS_MAX_INSTANCES) {
  919. return false;
  920. }
  921. return (get_accel_health(instance) && _use[instance]);
  922. }
  923. void
  924. AP_InertialSensor::_init_gyro()
  925. {
  926. uint8_t num_gyros = MIN(get_gyro_count(), INS_MAX_INSTANCES);
  927. Vector3f last_average[INS_MAX_INSTANCES], best_avg[INS_MAX_INSTANCES];
  928. Vector3f new_gyro_offset[INS_MAX_INSTANCES];
  929. float best_diff[INS_MAX_INSTANCES];
  930. bool converged[INS_MAX_INSTANCES];
  931. // exit immediately if calibration is already in progress
  932. if (_calibrating) {
  933. return;
  934. }
  935. // record we are calibrating
  936. _calibrating = true;
  937. // flash leds to tell user to keep the IMU still
  938. AP_Notify::flags.initialising = true;
  939. // cold start
  940. hal.console->printf("Init Gyro");
  941. /*
  942. we do the gyro calibration with no board rotation. This avoids
  943. having to rotate readings during the calibration
  944. */
  945. enum Rotation saved_orientation = _board_orientation;
  946. _board_orientation = ROTATION_NONE;
  947. // remove existing gyro offsets
  948. for (uint8_t k=0; k<num_gyros; k++) {
  949. _gyro_offset[k].set(Vector3f());
  950. new_gyro_offset[k].zero();
  951. best_diff[k] = -1.f;
  952. last_average[k].zero();
  953. converged[k] = false;
  954. }
  955. for(int8_t c = 0; c < 5; c++) {
  956. hal.scheduler->delay(5);
  957. update();
  958. }
  959. // the strategy is to average 50 points over 0.5 seconds, then do it
  960. // again and see if the 2nd average is within a small margin of
  961. // the first
  962. uint8_t num_converged = 0;
  963. // we try to get a good calibration estimate for up to 30 seconds
  964. // if the gyros are stable, we should get it in 1 second
  965. for (int16_t j = 0; j <= 30*4 && num_converged < num_gyros; j++) {
  966. Vector3f gyro_sum[INS_MAX_INSTANCES], gyro_avg[INS_MAX_INSTANCES], gyro_diff[INS_MAX_INSTANCES];
  967. Vector3f accel_start;
  968. float diff_norm[INS_MAX_INSTANCES];
  969. uint8_t i;
  970. EXPECT_DELAY_MS(1000);
  971. memset(diff_norm, 0, sizeof(diff_norm));
  972. hal.console->printf("*");
  973. for (uint8_t k=0; k<num_gyros; k++) {
  974. gyro_sum[k].zero();
  975. }
  976. accel_start = get_accel(0);
  977. for (i=0; i<50; i++) {
  978. update();
  979. for (uint8_t k=0; k<num_gyros; k++) {
  980. gyro_sum[k] += get_gyro(k);
  981. }
  982. hal.scheduler->delay(5);
  983. }
  984. Vector3f accel_diff = get_accel(0) - accel_start;
  985. if (accel_diff.length() > 0.2f) {
  986. // the accelerometers changed during the gyro sum. Skip
  987. // this sample. This copes with doing gyro cal on a
  988. // steadily moving platform. The value 0.2 corresponds
  989. // with around 5 degrees/second of rotation.
  990. continue;
  991. }
  992. for (uint8_t k=0; k<num_gyros; k++) {
  993. gyro_avg[k] = gyro_sum[k] / i;
  994. gyro_diff[k] = last_average[k] - gyro_avg[k];
  995. diff_norm[k] = gyro_diff[k].length();
  996. }
  997. for (uint8_t k=0; k<num_gyros; k++) {
  998. if (best_diff[k] < 0) {
  999. best_diff[k] = diff_norm[k];
  1000. best_avg[k] = gyro_avg[k];
  1001. } else if (gyro_diff[k].length() < ToRad(GYRO_INIT_MAX_DIFF_DPS)) {
  1002. // we want the average to be within 0.1 bit, which is 0.04 degrees/s
  1003. last_average[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
  1004. if (!converged[k] || last_average[k].length() < new_gyro_offset[k].length()) {
  1005. new_gyro_offset[k] = last_average[k];
  1006. }
  1007. if (!converged[k]) {
  1008. converged[k] = true;
  1009. num_converged++;
  1010. }
  1011. } else if (diff_norm[k] < best_diff[k]) {
  1012. best_diff[k] = diff_norm[k];
  1013. best_avg[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
  1014. }
  1015. last_average[k] = gyro_avg[k];
  1016. }
  1017. }
  1018. // we've kept the user waiting long enough - use the best pair we
  1019. // found so far
  1020. hal.console->printf("\n");
  1021. for (uint8_t k=0; k<num_gyros; k++) {
  1022. if (!converged[k]) {
  1023. hal.console->printf("gyro[%u] did not converge: diff=%f dps (expected < %f)\n",
  1024. (unsigned)k,
  1025. (double)ToDeg(best_diff[k]),
  1026. (double)GYRO_INIT_MAX_DIFF_DPS);
  1027. _gyro_offset[k] = best_avg[k];
  1028. // flag calibration as failed for this gyro
  1029. _gyro_cal_ok[k] = false;
  1030. } else {
  1031. _gyro_cal_ok[k] = true;
  1032. _gyro_offset[k] = new_gyro_offset[k];
  1033. }
  1034. }
  1035. // restore orientation
  1036. _board_orientation = saved_orientation;
  1037. // record calibration complete
  1038. _calibrating = false;
  1039. // stop flashing leds
  1040. AP_Notify::flags.initialising = false;
  1041. }
  1042. // save parameters to eeprom
  1043. void AP_InertialSensor::_save_gyro_calibration()
  1044. {
  1045. for (uint8_t i=0; i<_gyro_count; i++) {
  1046. _gyro_offset[i].save();
  1047. _gyro_id[i].save();
  1048. }
  1049. for (uint8_t i=_gyro_count; i<INS_MAX_INSTANCES; i++) {
  1050. _gyro_offset[i].set_and_save(Vector3f());
  1051. _gyro_id[i].set_and_save(0);
  1052. }
  1053. }
  1054. /*
  1055. update gyro and accel values from backends
  1056. */
  1057. void AP_InertialSensor::update(void)
  1058. {
  1059. // during initialisation update() may be called without
  1060. // wait_for_sample(), and a wait is implied
  1061. wait_for_sample();
  1062. if (!_hil_mode) {
  1063. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1064. // mark sensors unhealthy and let update() in each backend
  1065. // mark them healthy via _publish_gyro() and
  1066. // _publish_accel()
  1067. _gyro_healthy[i] = false;
  1068. _accel_healthy[i] = false;
  1069. _delta_velocity_valid[i] = false;
  1070. _delta_angle_valid[i] = false;
  1071. }
  1072. for (uint8_t i=0; i<_backend_count; i++) {
  1073. _backends[i]->update();
  1074. }
  1075. // clear accumulators
  1076. for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) {
  1077. _delta_velocity_acc[i].zero();
  1078. _delta_velocity_acc_dt[i] = 0;
  1079. _delta_angle_acc[i].zero();
  1080. _delta_angle_acc_dt[i] = 0;
  1081. }
  1082. if (!_startup_error_counts_set) {
  1083. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1084. _accel_startup_error_count[i] = _accel_error_count[i];
  1085. _gyro_startup_error_count[i] = _gyro_error_count[i];
  1086. }
  1087. if (_startup_ms == 0) {
  1088. _startup_ms = AP_HAL::millis();
  1089. } else if (AP_HAL::millis()-_startup_ms > 2000) {
  1090. _startup_error_counts_set = true;
  1091. }
  1092. }
  1093. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1094. if (_accel_error_count[i] < _accel_startup_error_count[i]) {
  1095. _accel_startup_error_count[i] = _accel_error_count[i];
  1096. }
  1097. if (_gyro_error_count[i] < _gyro_startup_error_count[i]) {
  1098. _gyro_startup_error_count[i] = _gyro_error_count[i];
  1099. }
  1100. }
  1101. // adjust health status if a sensor has a non-zero error count
  1102. // but another sensor doesn't.
  1103. bool have_zero_accel_error_count = false;
  1104. bool have_zero_gyro_error_count = false;
  1105. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1106. if (_accel_healthy[i] && _accel_error_count[i] <= _accel_startup_error_count[i]) {
  1107. have_zero_accel_error_count = true;
  1108. }
  1109. if (_gyro_healthy[i] && _gyro_error_count[i] <= _gyro_startup_error_count[i]) {
  1110. have_zero_gyro_error_count = true;
  1111. }
  1112. }
  1113. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1114. if (_gyro_healthy[i] && _gyro_error_count[i] > _gyro_startup_error_count[i] && have_zero_gyro_error_count) {
  1115. // we prefer not to use a gyro that has had errors
  1116. _gyro_healthy[i] = false;
  1117. }
  1118. if (_accel_healthy[i] && _accel_error_count[i] > _accel_startup_error_count[i] && have_zero_accel_error_count) {
  1119. // we prefer not to use a accel that has had errors
  1120. _accel_healthy[i] = false;
  1121. }
  1122. }
  1123. // set primary to first healthy accel and gyro
  1124. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1125. if (_gyro_healthy[i] && _use[i]) {
  1126. _primary_gyro = i;
  1127. break;
  1128. }
  1129. }
  1130. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  1131. if (_accel_healthy[i] && _use[i]) {
  1132. _primary_accel = i;
  1133. break;
  1134. }
  1135. }
  1136. }
  1137. _last_update_usec = AP_HAL::micros();
  1138. _have_sample = false;
  1139. }
  1140. /*
  1141. wait for a sample to be available. This is the function that
  1142. determines the timing of the main loop in ardupilot.
  1143. Ideally this function would return at exactly the rate given by the
  1144. sample_rate argument given to AP_InertialSensor::init().
  1145. The key output of this function is _delta_time, which is the time
  1146. over which the gyro and accel integration will happen for this
  1147. sample. We want that to be a constant time if possible, but if
  1148. delays occur we need to cope with them. The long term sum of
  1149. _delta_time should be exactly equal to the wall clock elapsed time
  1150. */
  1151. void AP_InertialSensor::wait_for_sample(void)
  1152. {
  1153. if (_have_sample) {
  1154. // the user has called wait_for_sample() again without
  1155. // consuming the sample with update()
  1156. return;
  1157. }
  1158. uint32_t now = AP_HAL::micros();
  1159. if (_next_sample_usec == 0 && _delta_time <= 0) {
  1160. // this is the first call to wait_for_sample()
  1161. _last_sample_usec = now - _sample_period_usec;
  1162. _next_sample_usec = now + _sample_period_usec;
  1163. goto check_sample;
  1164. }
  1165. // see how long it is till the next sample is due
  1166. if (_next_sample_usec - now <=_sample_period_usec) {
  1167. // we're ahead on time, schedule next sample at expected period
  1168. uint32_t wait_usec = _next_sample_usec - now;
  1169. hal.scheduler->delay_microseconds_boost(wait_usec);
  1170. uint32_t now2 = AP_HAL::micros();
  1171. if (now2+100 < _next_sample_usec) {
  1172. timing_printf("shortsleep %u\n", (unsigned)(_next_sample_usec-now2));
  1173. }
  1174. if (now2 > _next_sample_usec+400) {
  1175. timing_printf("longsleep %u wait_usec=%u\n",
  1176. (unsigned)(now2-_next_sample_usec),
  1177. (unsigned)wait_usec);
  1178. }
  1179. _next_sample_usec += _sample_period_usec;
  1180. } else if (now - _next_sample_usec < _sample_period_usec/8) {
  1181. // we've overshot, but only by a small amount, keep on
  1182. // schedule with no delay
  1183. timing_printf("overshoot1 %u\n", (unsigned)(now-_next_sample_usec));
  1184. _next_sample_usec += _sample_period_usec;
  1185. } else {
  1186. // we've overshot by a larger amount, re-zero scheduling with
  1187. // no delay
  1188. timing_printf("overshoot2 %u\n", (unsigned)(now-_next_sample_usec));
  1189. _next_sample_usec = now + _sample_period_usec;
  1190. }
  1191. check_sample:
  1192. if (!_hil_mode) {
  1193. // now we wait until we have the gyro and accel samples we need
  1194. uint8_t gyro_available_mask = 0;
  1195. uint8_t accel_available_mask = 0;
  1196. uint32_t wait_counter = 0;
  1197. while (true) {
  1198. for (uint8_t i=0; i<_backend_count; i++) {
  1199. // this is normally a nop, but can be used by backends
  1200. // that don't accumulate samples on a timer
  1201. _backends[i]->accumulate();
  1202. }
  1203. for (uint8_t i=0; i<_gyro_count; i++) {
  1204. if (_new_gyro_data[i]) {
  1205. const uint8_t imask = (1U<<i);
  1206. gyro_available_mask |= imask;
  1207. if (_use[i]) {
  1208. _gyro_wait_mask |= imask;
  1209. } else {
  1210. _gyro_wait_mask &= ~imask;
  1211. }
  1212. }
  1213. }
  1214. for (uint8_t i=0; i<_accel_count; i++) {
  1215. if (_new_accel_data[i]) {
  1216. const uint8_t imask = (1U<<i);
  1217. accel_available_mask |= imask;
  1218. if (_use[i]) {
  1219. _accel_wait_mask |= imask;
  1220. } else {
  1221. _accel_wait_mask &= ~imask;
  1222. }
  1223. }
  1224. }
  1225. // we wait for up to 800us to get all of the required
  1226. // accel and gyro samples. After that we accept at least
  1227. // one of each
  1228. if (wait_counter < 7) {
  1229. if (gyro_available_mask &&
  1230. ((gyro_available_mask & _gyro_wait_mask) == _gyro_wait_mask) &&
  1231. accel_available_mask &&
  1232. ((accel_available_mask & _accel_wait_mask) == _accel_wait_mask)) {
  1233. break;
  1234. }
  1235. } else {
  1236. if (gyro_available_mask && accel_available_mask) {
  1237. // reset the wait mask so we don't keep delaying
  1238. // for a dead IMU on the next loop. As soon as it
  1239. // comes back we will start waiting on it again
  1240. _gyro_wait_mask &= gyro_available_mask;
  1241. _accel_wait_mask &= accel_available_mask;
  1242. break;
  1243. }
  1244. }
  1245. hal.scheduler->delay_microseconds_boost(100);
  1246. wait_counter++;
  1247. }
  1248. }
  1249. now = AP_HAL::micros();
  1250. if (_hil_mode && _hil.delta_time > 0) {
  1251. _delta_time = _hil.delta_time;
  1252. _hil.delta_time = 0;
  1253. } else {
  1254. _delta_time = (now - _last_sample_usec) * 1.0e-6f;
  1255. }
  1256. _last_sample_usec = now;
  1257. #if 0
  1258. {
  1259. static uint64_t delta_time_sum;
  1260. static uint16_t counter;
  1261. if (delta_time_sum == 0) {
  1262. delta_time_sum = _sample_period_usec;
  1263. }
  1264. delta_time_sum += _delta_time * 1.0e6f;
  1265. if (counter++ == 400) {
  1266. counter = 0;
  1267. hal.console->printf("now=%lu _delta_time_sum=%lu diff=%ld\n",
  1268. (unsigned long)now,
  1269. (unsigned long)delta_time_sum,
  1270. (long)(now - delta_time_sum));
  1271. }
  1272. }
  1273. #endif
  1274. _have_sample = true;
  1275. }
  1276. /*
  1277. get delta angles
  1278. */
  1279. bool AP_InertialSensor::get_delta_angle(uint8_t i, Vector3f &delta_angle) const
  1280. {
  1281. if (_delta_angle_valid[i]) {
  1282. delta_angle = _delta_angle[i];
  1283. return true;
  1284. } else if (get_gyro_health(i)) {
  1285. // provide delta angle from raw gyro, so we use the same code
  1286. // at higher level
  1287. delta_angle = get_gyro(i) * get_delta_time();
  1288. return true;
  1289. }
  1290. return false;
  1291. }
  1292. /*
  1293. get delta velocity if available
  1294. */
  1295. bool AP_InertialSensor::get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
  1296. {
  1297. if (_delta_velocity_valid[i]) {
  1298. delta_velocity = _delta_velocity[i];
  1299. return true;
  1300. } else if (get_accel_health(i)) {
  1301. delta_velocity = get_accel(i) * get_delta_time();
  1302. return true;
  1303. }
  1304. return false;
  1305. }
  1306. /*
  1307. return delta_time for the delta_velocity
  1308. */
  1309. float AP_InertialSensor::get_delta_velocity_dt(uint8_t i) const
  1310. {
  1311. float ret;
  1312. if (_delta_velocity_valid[i]) {
  1313. ret = _delta_velocity_dt[i];
  1314. } else {
  1315. ret = get_delta_time();
  1316. }
  1317. ret = MIN(ret, _loop_delta_t_max);
  1318. return ret;
  1319. }
  1320. /*
  1321. return delta_time for the delta_angle
  1322. */
  1323. float AP_InertialSensor::get_delta_angle_dt(uint8_t i) const
  1324. {
  1325. float ret;
  1326. if (_delta_angle_valid[i] && _delta_angle_dt[i] > 0) {
  1327. ret = _delta_angle_dt[i];
  1328. } else {
  1329. ret = get_delta_time();
  1330. }
  1331. ret = MIN(ret, _loop_delta_t_max);
  1332. return ret;
  1333. }
  1334. /*
  1335. support for setting accel and gyro vectors, for use by HIL
  1336. */
  1337. void AP_InertialSensor::set_accel(uint8_t instance, const Vector3f &accel)
  1338. {
  1339. if (_accel_count == 0) {
  1340. // we haven't initialised yet
  1341. return;
  1342. }
  1343. if (instance < INS_MAX_INSTANCES) {
  1344. _accel[instance] = accel;
  1345. _accel_healthy[instance] = true;
  1346. if (_accel_count <= instance) {
  1347. _accel_count = instance+1;
  1348. }
  1349. if (!_accel_healthy[_primary_accel]) {
  1350. _primary_accel = instance;
  1351. }
  1352. }
  1353. }
  1354. void AP_InertialSensor::set_gyro(uint8_t instance, const Vector3f &gyro)
  1355. {
  1356. if (_gyro_count == 0) {
  1357. // we haven't initialised yet
  1358. return;
  1359. }
  1360. if (instance < INS_MAX_INSTANCES) {
  1361. _gyro[instance] = gyro;
  1362. _gyro_healthy[instance] = true;
  1363. if (_gyro_count <= instance) {
  1364. _gyro_count = instance+1;
  1365. _gyro_cal_ok[instance] = true;
  1366. }
  1367. if (!_accel_healthy[_primary_accel]) {
  1368. _primary_accel = instance;
  1369. }
  1370. }
  1371. }
  1372. /*
  1373. set delta time for next ins.update()
  1374. */
  1375. void AP_InertialSensor::set_delta_time(float delta_time)
  1376. {
  1377. _hil.delta_time = delta_time;
  1378. }
  1379. /*
  1380. set delta velocity for next update
  1381. */
  1382. void AP_InertialSensor::set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav)
  1383. {
  1384. if (instance < INS_MAX_INSTANCES) {
  1385. _delta_velocity_valid[instance] = true;
  1386. _delta_velocity[instance] = deltav;
  1387. _delta_velocity_dt[instance] = deltavt;
  1388. }
  1389. }
  1390. /*
  1391. set delta angle for next update
  1392. */
  1393. void AP_InertialSensor::set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat)
  1394. {
  1395. if (instance < INS_MAX_INSTANCES) {
  1396. _delta_angle_valid[instance] = true;
  1397. _delta_angle[instance] = deltaa;
  1398. _delta_angle_dt[instance] = deltaat;
  1399. }
  1400. }
  1401. /*
  1402. * Get an AuxiliaryBus of N @instance of backend identified by @backend_id
  1403. */
  1404. AuxiliaryBus *AP_InertialSensor::get_auxiliary_bus(int16_t backend_id, uint8_t instance)
  1405. {
  1406. detect_backends();
  1407. AP_InertialSensor_Backend *backend = _find_backend(backend_id, instance);
  1408. if (backend == nullptr) {
  1409. return nullptr;
  1410. }
  1411. return backend->get_auxiliary_bus();
  1412. }
  1413. // calculate vibration levels and check for accelerometer clipping (called by a backends)
  1414. void AP_InertialSensor::calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt)
  1415. {
  1416. // check for clipping
  1417. if (_backends[instance] == nullptr) {
  1418. return;
  1419. }
  1420. if (fabsf(accel.x) > _backends[instance]->get_clip_limit() ||
  1421. fabsf(accel.y) > _backends[instance]->get_clip_limit() ||
  1422. fabsf(accel.z) > _backends[instance]->get_clip_limit()) {
  1423. _accel_clip_count[instance]++;
  1424. }
  1425. // calculate vibration levels
  1426. if (instance < INS_VIBRATION_CHECK_INSTANCES) {
  1427. // filter accel at 5hz
  1428. Vector3f accel_filt = _accel_vibe_floor_filter[instance].apply(accel, dt);
  1429. // calc difference from this sample and 5hz filtered value, square and filter at 2hz
  1430. Vector3f accel_diff = (accel - accel_filt);
  1431. accel_diff.x *= accel_diff.x;
  1432. accel_diff.y *= accel_diff.y;
  1433. accel_diff.z *= accel_diff.z;
  1434. _accel_vibe_filter[instance].apply(accel_diff, dt);
  1435. }
  1436. }
  1437. // peak hold detector for slower mechanisms to detect spikes
  1438. void AP_InertialSensor::set_accel_peak_hold(uint8_t instance, const Vector3f &accel)
  1439. {
  1440. if (instance != _primary_accel) {
  1441. // we only record for primary accel
  1442. return;
  1443. }
  1444. uint32_t now = AP_HAL::millis();
  1445. // negative x peak(min) hold detector
  1446. if (accel.x < _peak_hold_state.accel_peak_hold_neg_x ||
  1447. _peak_hold_state.accel_peak_hold_neg_x_age <= now) {
  1448. _peak_hold_state.accel_peak_hold_neg_x = accel.x;
  1449. _peak_hold_state.accel_peak_hold_neg_x_age = now + AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS;
  1450. }
  1451. }
  1452. // retrieve latest calculated vibration levels
  1453. Vector3f AP_InertialSensor::get_vibration_levels(uint8_t instance) const
  1454. {
  1455. Vector3f vibe;
  1456. if (instance < INS_VIBRATION_CHECK_INSTANCES) {
  1457. vibe = _accel_vibe_filter[instance].get();
  1458. vibe.x = safe_sqrt(vibe.x);
  1459. vibe.y = safe_sqrt(vibe.y);
  1460. vibe.z = safe_sqrt(vibe.z);
  1461. }
  1462. return vibe;
  1463. }
  1464. // check for vibration movement. Return true if all axis show nearly zero movement
  1465. bool AP_InertialSensor::is_still()
  1466. {
  1467. Vector3f vibe = get_vibration_levels();
  1468. return (vibe.x < _still_threshold) &&
  1469. (vibe.y < _still_threshold) &&
  1470. (vibe.z < _still_threshold);
  1471. }
  1472. // initialise and register accel calibrator
  1473. // called during the startup of accel cal
  1474. void AP_InertialSensor::acal_init()
  1475. {
  1476. // NOTE: these objects are never deallocated because the pre-arm checks force a reboot
  1477. if (_acal == nullptr) {
  1478. _acal = new AP_AccelCal;
  1479. }
  1480. if (_accel_calibrator == nullptr) {
  1481. _accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES];
  1482. }
  1483. }
  1484. // update accel calibrator
  1485. void AP_InertialSensor::acal_update()
  1486. {
  1487. if(_acal == nullptr) {
  1488. return;
  1489. }
  1490. EXPECT_DELAY_MS(20000);
  1491. _acal->update();
  1492. if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) {
  1493. _acal->cancel();
  1494. }
  1495. }
  1496. // Update the harmonic notch frequency
  1497. void AP_InertialSensor::update_harmonic_notch_freq_hz(float scaled_freq) {
  1498. // protect against zero as the scaled frequency
  1499. if (is_positive(scaled_freq)) {
  1500. _calculated_harmonic_notch_freq_hz = scaled_freq;
  1501. }
  1502. }
  1503. /*
  1504. set and save accelerometer bias along with trim calculation
  1505. */
  1506. void AP_InertialSensor::_acal_save_calibrations()
  1507. {
  1508. Vector3f bias, gain;
  1509. for (uint8_t i=0; i<_accel_count; i++) {
  1510. if (_accel_calibrator[i].get_status() == ACCEL_CAL_SUCCESS) {
  1511. _accel_calibrator[i].get_calibration(bias, gain);
  1512. _accel_offset[i].set_and_save(bias);
  1513. _accel_scale[i].set_and_save(gain);
  1514. _accel_id[i].save();
  1515. _accel_id_ok[i] = true;
  1516. } else {
  1517. _accel_offset[i].set_and_save(Vector3f());
  1518. _accel_scale[i].set_and_save(Vector3f());
  1519. }
  1520. }
  1521. // clear any unused accels
  1522. for (uint8_t i=_accel_count; i<INS_MAX_INSTANCES; i++) {
  1523. _accel_id[i].set_and_save(0);
  1524. _accel_offset[i].set_and_save(Vector3f());
  1525. _accel_scale[i].set_and_save(Vector3f());
  1526. }
  1527. Vector3f aligned_sample;
  1528. Vector3f misaligned_sample;
  1529. switch(_trim_option) {
  1530. case 0:
  1531. break;
  1532. case 1:
  1533. // The first level step of accel cal will be taken as gnd truth,
  1534. // i.e. trim will be set as per the output of primary accel from the level step
  1535. get_primary_accel_cal_sample_avg(0,aligned_sample);
  1536. _trim_pitch = atan2f(aligned_sample.x, norm(aligned_sample.y, aligned_sample.z));
  1537. _trim_roll = atan2f(-aligned_sample.y, -aligned_sample.z);
  1538. _new_trim = true;
  1539. break;
  1540. case 2:
  1541. // Reference accel is truth, in this scenario there is a reference accel
  1542. // as mentioned in ACC_BODY_ALIGNED
  1543. if (get_primary_accel_cal_sample_avg(0,misaligned_sample) && get_fixed_mount_accel_cal_sample(0,aligned_sample)) {
  1544. // determine trim from aligned sample vs misaligned sample
  1545. Vector3f cross = (misaligned_sample%aligned_sample);
  1546. float dot = (misaligned_sample*aligned_sample);
  1547. Quaternion q(safe_sqrt(sq(misaligned_sample.length())*sq(aligned_sample.length()))+dot, cross.x, cross.y, cross.z);
  1548. q.normalize();
  1549. _trim_roll = q.get_euler_roll();
  1550. _trim_pitch = q.get_euler_pitch();
  1551. _new_trim = true;
  1552. }
  1553. break;
  1554. default:
  1555. _new_trim = false;
  1556. /* no break */
  1557. }
  1558. if (fabsf(_trim_roll) > radians(10) ||
  1559. fabsf(_trim_pitch) > radians(10)) {
  1560. hal.console->printf("ERR: Trim over maximum of 10 degrees!!");
  1561. _new_trim = false; //we have either got faulty level during acal or highly misaligned accelerometers
  1562. }
  1563. _accel_cal_requires_reboot = true;
  1564. }
  1565. void AP_InertialSensor::_acal_event_failure()
  1566. {
  1567. for (uint8_t i=0; i<_accel_count; i++) {
  1568. _accel_offset[i].set_and_notify(Vector3f(0,0,0));
  1569. _accel_scale[i].set_and_notify(Vector3f(1,1,1));
  1570. }
  1571. }
  1572. /*
  1573. Returns true if new valid trim values are available and passes them to reference vars
  1574. */
  1575. bool AP_InertialSensor::get_new_trim(float& trim_roll, float &trim_pitch)
  1576. {
  1577. if (_new_trim) {
  1578. trim_roll = _trim_roll;
  1579. trim_pitch = _trim_pitch;
  1580. _new_trim = false;
  1581. return true;
  1582. }
  1583. return false;
  1584. }
  1585. /*
  1586. Returns body fixed accelerometer level data averaged during accel calibration's first step
  1587. */
  1588. bool AP_InertialSensor::get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vector3f& ret) const
  1589. {
  1590. if (_accel_count <= (_acc_body_aligned-1) || _accel_calibrator[2].get_status() != ACCEL_CAL_SUCCESS || sample_num>=_accel_calibrator[2].get_num_samples_collected()) {
  1591. return false;
  1592. }
  1593. _accel_calibrator[_acc_body_aligned-1].get_sample_corrected(sample_num, ret);
  1594. if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) {
  1595. ret = *_custom_rotation * ret;
  1596. } else {
  1597. ret.rotate(_board_orientation);
  1598. }
  1599. return true;
  1600. }
  1601. /*
  1602. Returns Primary accelerometer level data averaged during accel calibration's first step
  1603. */
  1604. bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vector3f& ret) const
  1605. {
  1606. uint8_t count = 0;
  1607. Vector3f avg = Vector3f(0,0,0);
  1608. for (uint8_t i=0; i<MIN(_accel_count,2); i++) {
  1609. if (_accel_calibrator[i].get_status() != ACCEL_CAL_SUCCESS || sample_num>=_accel_calibrator[i].get_num_samples_collected()) {
  1610. continue;
  1611. }
  1612. Vector3f sample;
  1613. _accel_calibrator[i].get_sample_corrected(sample_num, sample);
  1614. avg += sample;
  1615. count++;
  1616. }
  1617. if (count == 0) {
  1618. return false;
  1619. }
  1620. avg /= count;
  1621. ret = avg;
  1622. if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) {
  1623. ret = *_custom_rotation * ret;
  1624. } else {
  1625. ret.rotate(_board_orientation);
  1626. }
  1627. return true;
  1628. }
  1629. /*
  1630. perform a simple 1D accel calibration, returning mavlink result code
  1631. */
  1632. MAV_RESULT AP_InertialSensor::simple_accel_cal()
  1633. {
  1634. uint8_t num_accels = MIN(get_accel_count(), INS_MAX_INSTANCES);
  1635. Vector3f last_average[INS_MAX_INSTANCES];
  1636. Vector3f new_accel_offset[INS_MAX_INSTANCES];
  1637. Vector3f saved_offsets[INS_MAX_INSTANCES];
  1638. Vector3f saved_scaling[INS_MAX_INSTANCES];
  1639. bool converged[INS_MAX_INSTANCES];
  1640. const float accel_convergence_limit = 0.05;
  1641. Vector3f rotated_gravity(0, 0, -GRAVITY_MSS);
  1642. // exit immediately if calibration is already in progress
  1643. if (_calibrating) {
  1644. return MAV_RESULT_TEMPORARILY_REJECTED;
  1645. }
  1646. EXPECT_DELAY_MS(20000);
  1647. // record we are calibrating
  1648. _calibrating = true;
  1649. // flash leds to tell user to keep the IMU still
  1650. AP_Notify::flags.initialising = true;
  1651. hal.console->printf("Simple accel cal");
  1652. /*
  1653. we do the accel calibration with no board rotation. This avoids
  1654. having to rotate readings during the calibration
  1655. */
  1656. enum Rotation saved_orientation = _board_orientation;
  1657. _board_orientation = ROTATION_NONE;
  1658. // get the rotated gravity vector which will need to be applied to the offsets
  1659. rotated_gravity.rotate_inverse(saved_orientation);
  1660. // save existing accel offsets
  1661. for (uint8_t k=0; k<num_accels; k++) {
  1662. saved_offsets[k] = _accel_offset[k];
  1663. saved_scaling[k] = _accel_scale[k];
  1664. }
  1665. // remove existing accel offsets and scaling
  1666. for (uint8_t k=0; k<num_accels; k++) {
  1667. _accel_offset[k].set(Vector3f());
  1668. _accel_scale[k].set(Vector3f(1,1,1));
  1669. new_accel_offset[k].zero();
  1670. last_average[k].zero();
  1671. converged[k] = false;
  1672. }
  1673. for (uint8_t c = 0; c < 5; c++) {
  1674. hal.scheduler->delay(5);
  1675. update();
  1676. }
  1677. // the strategy is to average 50 points over 0.5 seconds, then do it
  1678. // again and see if the 2nd average is within a small margin of
  1679. // the first
  1680. uint8_t num_converged = 0;
  1681. // we try to get a good calibration estimate for up to 10 seconds
  1682. // if the accels are stable, we should get it in 1 second
  1683. for (int16_t j = 0; j <= 10*4 && num_converged < num_accels; j++) {
  1684. Vector3f accel_sum[INS_MAX_INSTANCES], accel_avg[INS_MAX_INSTANCES], accel_diff[INS_MAX_INSTANCES];
  1685. float diff_norm[INS_MAX_INSTANCES];
  1686. uint8_t i;
  1687. memset(diff_norm, 0, sizeof(diff_norm));
  1688. hal.console->printf("*");
  1689. for (uint8_t k=0; k<num_accels; k++) {
  1690. accel_sum[k].zero();
  1691. }
  1692. for (i=0; i<50; i++) {
  1693. update();
  1694. for (uint8_t k=0; k<num_accels; k++) {
  1695. accel_sum[k] += get_accel(k);
  1696. }
  1697. hal.scheduler->delay(5);
  1698. }
  1699. for (uint8_t k=0; k<num_accels; k++) {
  1700. accel_avg[k] = accel_sum[k] / i;
  1701. accel_diff[k] = last_average[k] - accel_avg[k];
  1702. diff_norm[k] = accel_diff[k].length();
  1703. }
  1704. for (uint8_t k=0; k<num_accels; k++) {
  1705. if (j > 0 && diff_norm[k] < accel_convergence_limit) {
  1706. last_average[k] = (accel_avg[k] * 0.5f) + (last_average[k] * 0.5f);
  1707. if (!converged[k] || last_average[k].length() < new_accel_offset[k].length()) {
  1708. new_accel_offset[k] = last_average[k];
  1709. }
  1710. if (!converged[k]) {
  1711. converged[k] = true;
  1712. num_converged++;
  1713. }
  1714. } else {
  1715. last_average[k] = accel_avg[k];
  1716. }
  1717. }
  1718. }
  1719. MAV_RESULT result = MAV_RESULT_ACCEPTED;
  1720. // see if we've passed
  1721. for (uint8_t k=0; k<num_accels; k++) {
  1722. if (!converged[k]) {
  1723. result = MAV_RESULT_FAILED;
  1724. }
  1725. }
  1726. // restore orientation
  1727. _board_orientation = saved_orientation;
  1728. if (result == MAV_RESULT_ACCEPTED) {
  1729. hal.console->printf("\nPASSED\n");
  1730. for (uint8_t k=0; k<num_accels; k++) {
  1731. // remove rotated gravity
  1732. new_accel_offset[k] -= rotated_gravity;
  1733. _accel_offset[k].set_and_save(new_accel_offset[k]);
  1734. _accel_scale[k].save();
  1735. _accel_id[k].save();
  1736. _accel_id_ok[k] = true;
  1737. }
  1738. // force trim to zero
  1739. AP::ahrs().set_trim(Vector3f(0, 0, 0));
  1740. } else {
  1741. hal.console->printf("\nFAILED\n");
  1742. // restore old values
  1743. for (uint8_t k=0; k<num_accels; k++) {
  1744. _accel_offset[k] = saved_offsets[k];
  1745. _accel_scale[k] = saved_scaling[k];
  1746. }
  1747. }
  1748. // record calibration complete
  1749. _calibrating = false;
  1750. // throw away any existing samples that may have the wrong
  1751. // orientation. We do this by throwing samples away for 0.5s,
  1752. // which is enough time for the filters to settle
  1753. uint32_t start_ms = AP_HAL::millis();
  1754. while (AP_HAL::millis() - start_ms < 500) {
  1755. update();
  1756. }
  1757. // and reset state estimators
  1758. AP::ahrs().reset();
  1759. // stop flashing leds
  1760. AP_Notify::flags.initialising = false;
  1761. return result;
  1762. }
  1763. /*
  1764. see if gyro calibration should be performed
  1765. */
  1766. AP_InertialSensor::Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_timing()
  1767. {
  1768. if (hal.util->was_watchdog_reset()) {
  1769. return GYRO_CAL_NEVER;
  1770. }
  1771. return (Gyro_Calibration_Timing)_gyro_cal_timing.get();
  1772. }
  1773. #if !HAL_MINIMIZE_FEATURES
  1774. /*
  1775. update IMU kill mask, used for testing IMU failover
  1776. */
  1777. void AP_InertialSensor::kill_imu(uint8_t imu_idx, bool kill_it)
  1778. {
  1779. if (kill_it) {
  1780. uint8_t new_kill_mask = imu_kill_mask | (1U<<imu_idx);
  1781. // don't allow the last IMU to be killed
  1782. bool all_dead = true;
  1783. for (uint8_t i=0; i<MIN(_gyro_count, _accel_count); i++) {
  1784. if (use_gyro(i) && use_accel(i) && !(new_kill_mask & (1U<<i))) {
  1785. // we have at least one healthy IMU left
  1786. all_dead = false;
  1787. }
  1788. }
  1789. if (!all_dead) {
  1790. imu_kill_mask = new_kill_mask;
  1791. }
  1792. } else {
  1793. imu_kill_mask &= ~(1U<<imu_idx);
  1794. }
  1795. }
  1796. #endif // HAL_MINIMIZE_FEATURES
  1797. namespace AP {
  1798. AP_InertialSensor &ins()
  1799. {
  1800. return *AP_InertialSensor::get_singleton();
  1801. }
  1802. };