AP_NavEKF3_Logging.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359
  1. #include "AP_NavEKF3.h"
  2. #include <AP_HAL/HAL.h>
  3. #include <AP_Logger/AP_Logger.h>
  4. void NavEKF3::Log_Write_EKF1(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  5. {
  6. // Write first EKF packet
  7. Vector3f euler;
  8. Vector2f posNE;
  9. float posD;
  10. Vector3f velNED;
  11. Vector3f gyroBias;
  12. float posDownDeriv;
  13. Location originLLH;
  14. getEulerAngles(_core,euler);
  15. getVelNED(_core,velNED);
  16. getPosNE(_core,posNE);
  17. getPosD(_core,posD);
  18. getGyroBias(_core,gyroBias);
  19. posDownDeriv = getPosDownDerivative(_core);
  20. if (!getOriginLLH(_core,originLLH)) {
  21. originLLH.alt = 0;
  22. }
  23. const struct log_EKF1 pkt{
  24. LOG_PACKET_HEADER_INIT(msg_id),
  25. time_us : time_us,
  26. roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
  27. pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
  28. yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
  29. velN : (float)(velNED.x), // velocity North (m/s)
  30. velE : (float)(velNED.y), // velocity East (m/s)
  31. velD : (float)(velNED.z), // velocity Down (m/s)
  32. posD_dot : (float)(posDownDeriv), // first derivative of down position
  33. posN : (float)(posNE.x), // metres North
  34. posE : (float)(posNE.y), // metres East
  35. posD : (float)(posD), // metres Down
  36. gyrX : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
  37. gyrY : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
  38. gyrZ : (int16_t)(100*degrees(gyroBias.z)), // cd/sec, displayed as deg/sec due to format string
  39. originHgt : originLLH.alt // WGS-84 altitude of EKF origin in cm
  40. };
  41. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  42. }
  43. void NavEKF3::Log_Write_NKF2a(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  44. {
  45. // Write second EKF packet
  46. Vector3f accelBias;
  47. Vector3f wind;
  48. Vector3f magNED;
  49. Vector3f magXYZ;
  50. uint8_t magIndex = getActiveMag(_core);
  51. getAccelBias(_core,accelBias);
  52. getWind(_core,wind);
  53. getMagNED(_core,magNED);
  54. getMagXYZ(_core,magXYZ);
  55. const struct log_NKF2a pkt2{
  56. LOG_PACKET_HEADER_INIT(msg_id),
  57. time_us : time_us,
  58. accBiasX : (int16_t)(100*accelBias.x),
  59. accBiasY : (int16_t)(100*accelBias.y),
  60. accBiasZ : (int16_t)(100*accelBias.z),
  61. windN : (int16_t)(100*wind.x),
  62. windE : (int16_t)(100*wind.y),
  63. magN : (int16_t)(magNED.x),
  64. magE : (int16_t)(magNED.y),
  65. magD : (int16_t)(magNED.z),
  66. magX : (int16_t)(magXYZ.x),
  67. magY : (int16_t)(magXYZ.y),
  68. magZ : (int16_t)(magXYZ.z),
  69. index : (uint8_t)(magIndex)
  70. };
  71. AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
  72. }
  73. void NavEKF3::Log_Write_NKF3(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  74. {
  75. // Write third EKF packet
  76. Vector3f velInnov;
  77. Vector3f posInnov;
  78. Vector3f magInnov;
  79. float tasInnov = 0;
  80. float yawInnov = 0;
  81. getInnovations(_core,velInnov, posInnov, magInnov, tasInnov, yawInnov);
  82. const struct log_NKF3 pkt3{
  83. LOG_PACKET_HEADER_INIT(msg_id),
  84. time_us : time_us,
  85. innovVN : (int16_t)(100*velInnov.x),
  86. innovVE : (int16_t)(100*velInnov.y),
  87. innovVD : (int16_t)(100*velInnov.z),
  88. innovPN : (int16_t)(100*posInnov.x),
  89. innovPE : (int16_t)(100*posInnov.y),
  90. innovPD : (int16_t)(100*posInnov.z),
  91. innovMX : (int16_t)(magInnov.x),
  92. innovMY : (int16_t)(magInnov.y),
  93. innovMZ : (int16_t)(magInnov.z),
  94. innovYaw : (int16_t)(100*degrees(yawInnov)),
  95. innovVT : (int16_t)(100*tasInnov)
  96. };
  97. AP::logger().WriteBlock(&pkt3, sizeof(pkt3));
  98. }
  99. void NavEKF3::Log_Write_NKF4(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  100. {
  101. // Write fourth EKF packet
  102. float velVar = 0;
  103. float posVar = 0;
  104. float hgtVar = 0;
  105. Vector3f magVar;
  106. float tasVar = 0;
  107. Vector2f offset;
  108. uint16_t faultStatus=0;
  109. uint8_t timeoutStatus=0;
  110. nav_filter_status solutionStatus {};
  111. nav_gps_status gpsStatus {};
  112. getVariances(_core,velVar, posVar, hgtVar, magVar, tasVar, offset);
  113. float tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
  114. getFilterFaults(_core,faultStatus);
  115. getFilterTimeouts(_core,timeoutStatus);
  116. getFilterStatus(_core,solutionStatus);
  117. getFilterGpsStatus(_core,gpsStatus);
  118. float tiltError;
  119. getTiltError(_core,tiltError);
  120. uint8_t primaryIndex = getPrimaryCoreIndex();
  121. const struct log_NKF4 pkt4{
  122. LOG_PACKET_HEADER_INIT(msg_id),
  123. time_us : time_us,
  124. sqrtvarV : (int16_t)(100*velVar),
  125. sqrtvarP : (int16_t)(100*posVar),
  126. sqrtvarH : (int16_t)(100*hgtVar),
  127. sqrtvarM : (int16_t)(100*tempVar),
  128. sqrtvarVT : (int16_t)(100*tasVar),
  129. tiltErr : (float)tiltError,
  130. offsetNorth : (int8_t)(offset.x),
  131. offsetEast : (int8_t)(offset.y),
  132. faults : (uint16_t)(faultStatus),
  133. timeouts : (uint8_t)(timeoutStatus),
  134. solution : (uint16_t)(solutionStatus.value),
  135. gps : (uint16_t)(gpsStatus.value),
  136. primary : (int8_t)primaryIndex
  137. };
  138. AP::logger().WriteBlock(&pkt4, sizeof(pkt4));
  139. }
  140. void NavEKF3::Log_Write_NKF5(uint64_t time_us) const
  141. {
  142. // Write fifth EKF packet - take data from the primary instance
  143. float normInnov=0; // normalised innovation variance ratio for optical flow observations fused by the main nav filter
  144. float gndOffset=0; // estimated vertical position of the terrain relative to the nav filter zero datum
  145. float flowInnovX=0, flowInnovY=0; // optical flow LOS rate vector innovations from the main nav filter
  146. float auxFlowInnov=0; // optical flow LOS rate innovation from terrain offset estimator
  147. float HAGL=0; // height above ground level
  148. float rngInnov=0; // range finder innovations
  149. float range=0; // measured range
  150. float gndOffsetErr=0; // filter ground offset state error
  151. Vector3f predictorErrors; // output predictor angle, velocity and position tracking error
  152. getFlowDebug(-1,normInnov, gndOffset, flowInnovX, flowInnovY, auxFlowInnov, HAGL, rngInnov, range, gndOffsetErr);
  153. getOutputTrackingError(-1,predictorErrors);
  154. const struct log_NKF5 pkt5{
  155. LOG_PACKET_HEADER_INIT(LOG_XKF5_MSG),
  156. time_us : time_us,
  157. normInnov : (uint8_t)(MIN(100*normInnov,255)),
  158. FIX : (int16_t)(1000*flowInnovX),
  159. FIY : (int16_t)(1000*flowInnovY),
  160. AFI : (int16_t)(1000*auxFlowInnov),
  161. HAGL : (int16_t)(100*HAGL),
  162. offset : (int16_t)(100*gndOffset),
  163. RI : (int16_t)(100*rngInnov),
  164. meaRng : (uint16_t)(100*range),
  165. errHAGL : (uint16_t)(100*gndOffsetErr),
  166. angErr : (float)predictorErrors.x,
  167. velErr : (float)predictorErrors.y,
  168. posErr : (float)predictorErrors.z
  169. };
  170. AP::logger().WriteBlock(&pkt5, sizeof(pkt5));
  171. }
  172. void NavEKF3::Log_Write_Quaternion(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  173. {
  174. // log quaternion
  175. Quaternion quat;
  176. getQuaternion(_core, quat);
  177. const struct log_Quaternion pktq1{
  178. LOG_PACKET_HEADER_INIT(msg_id),
  179. time_us : time_us,
  180. q1 : quat.q1,
  181. q2 : quat.q2,
  182. q3 : quat.q3,
  183. q4 : quat.q4
  184. };
  185. AP::logger().WriteBlock(&pktq1, sizeof(pktq1));
  186. }
  187. void NavEKF3::Log_Write_Beacon(uint64_t time_us) const
  188. {
  189. // write range beacon fusion debug packet if the range value is non-zero
  190. uint8_t ID;
  191. float rng;
  192. float innovVar;
  193. float innov;
  194. float testRatio;
  195. Vector3f beaconPosNED;
  196. float bcnPosOffsetHigh;
  197. float bcnPosOffsetLow;
  198. Vector3f posNED;
  199. if (getRangeBeaconDebug(-1, ID, rng, innov, innovVar, testRatio, beaconPosNED, bcnPosOffsetHigh, bcnPosOffsetLow, posNED)) {
  200. if (rng > 0.0f) {
  201. const struct log_RngBcnDebug pkt10{
  202. LOG_PACKET_HEADER_INIT(LOG_XKF10_MSG),
  203. time_us : time_us,
  204. ID : (uint8_t)ID,
  205. rng : (int16_t)(100*rng),
  206. innov : (int16_t)(100*innov),
  207. sqrtInnovVar : (uint16_t)(100*sqrtf(innovVar)),
  208. testRatio : (uint16_t)(100*constrain_float(testRatio,0.0f,650.0f)),
  209. beaconPosN : (int16_t)(100*beaconPosNED.x),
  210. beaconPosE : (int16_t)(100*beaconPosNED.y),
  211. beaconPosD : (int16_t)(100*beaconPosNED.z),
  212. offsetHigh : (int16_t)(100*bcnPosOffsetHigh),
  213. offsetLow : (int16_t)(100*bcnPosOffsetLow),
  214. posN : (int16_t)(100*posNED.x),
  215. posE : (int16_t)(100*posNED.y),
  216. posD : (int16_t)(100*posNED.z)
  217. };
  218. AP::logger().WriteBlock(&pkt10, sizeof(pkt10));
  219. }
  220. }
  221. }
  222. void NavEKF3::Log_Write_BodyOdom(uint64_t time_us) const
  223. {
  224. Vector3f velBodyInnov,velBodyInnovVar;
  225. static uint32_t lastUpdateTime_ms = 0;
  226. uint32_t updateTime_ms = getBodyFrameOdomDebug(-1, velBodyInnov, velBodyInnovVar);
  227. if (updateTime_ms > lastUpdateTime_ms) {
  228. const struct log_ekfBodyOdomDebug pkt11{
  229. LOG_PACKET_HEADER_INIT(LOG_XKFD_MSG),
  230. time_us : time_us,
  231. velInnovX : velBodyInnov.x,
  232. velInnovY : velBodyInnov.y,
  233. velInnovZ : velBodyInnov.z,
  234. velInnovVarX : velBodyInnovVar.x,
  235. velInnovVarY : velBodyInnovVar.y,
  236. velInnovVarZ : velBodyInnovVar.z
  237. };
  238. AP::logger().WriteBlock(&pkt11, sizeof(pkt11));
  239. lastUpdateTime_ms = updateTime_ms;
  240. }
  241. }
  242. void NavEKF3::Log_Write_State_Variances(uint64_t time_us) const
  243. {
  244. static uint32_t lastEkfStateVarLogTime_ms = 0;
  245. if (AP_HAL::millis() - lastEkfStateVarLogTime_ms > 490) {
  246. lastEkfStateVarLogTime_ms = AP_HAL::millis();
  247. float stateVar[24];
  248. getStateVariances(-1, stateVar);
  249. const struct log_ekfStateVar pktv1{
  250. LOG_PACKET_HEADER_INIT(LOG_XKV1_MSG),
  251. time_us : time_us,
  252. v00 : stateVar[0],
  253. v01 : stateVar[1],
  254. v02 : stateVar[2],
  255. v03 : stateVar[3],
  256. v04 : stateVar[4],
  257. v05 : stateVar[5],
  258. v06 : stateVar[6],
  259. v07 : stateVar[7],
  260. v08 : stateVar[8],
  261. v09 : stateVar[9],
  262. v10 : stateVar[10],
  263. v11 : stateVar[11]
  264. };
  265. AP::logger().WriteBlock(&pktv1, sizeof(pktv1));
  266. const struct log_ekfStateVar pktv2{
  267. LOG_PACKET_HEADER_INIT(LOG_XKV2_MSG),
  268. time_us : time_us,
  269. v00 : stateVar[12],
  270. v01 : stateVar[13],
  271. v02 : stateVar[14],
  272. v03 : stateVar[15],
  273. v04 : stateVar[16],
  274. v05 : stateVar[17],
  275. v06 : stateVar[18],
  276. v07 : stateVar[19],
  277. v08 : stateVar[20],
  278. v09 : stateVar[21],
  279. v10 : stateVar[22],
  280. v11 : stateVar[23]
  281. };
  282. AP::logger().WriteBlock(&pktv2, sizeof(pktv2));
  283. }
  284. }
  285. void NavEKF3::Log_Write()
  286. {
  287. // only log if enabled
  288. if (activeCores() <= 0) {
  289. return;
  290. }
  291. uint64_t time_us = AP_HAL::micros64();
  292. Log_Write_EKF1(0, LOG_XKF1_MSG, time_us);
  293. Log_Write_NKF2a(0, LOG_XKF2_MSG, time_us);
  294. Log_Write_NKF3(0, LOG_XKF3_MSG, time_us);
  295. Log_Write_NKF4(0, LOG_XKF4_MSG, time_us);
  296. Log_Write_NKF5(time_us);
  297. Log_Write_Quaternion(0, LOG_XKQ1_MSG, time_us);
  298. // log EKF state info for the second EFK core if enabled
  299. if (activeCores() >= 2) {
  300. Log_Write_EKF1(1, LOG_XKF6_MSG, time_us);
  301. Log_Write_NKF2a(1, LOG_XKF7_MSG, time_us);
  302. Log_Write_NKF3(1, LOG_XKF8_MSG, time_us);
  303. Log_Write_NKF4(1, LOG_XKF9_MSG, time_us);
  304. Log_Write_Quaternion(1, LOG_XKQ2_MSG, time_us);
  305. }
  306. // log EKF state info for the third EFK core if enabled
  307. if (activeCores() >= 3) {
  308. Log_Write_EKF1(2, LOG_XKF11_MSG, time_us);
  309. Log_Write_NKF2a(2, LOG_XKF12_MSG, time_us);
  310. Log_Write_NKF3(2, LOG_XKF13_MSG, time_us);
  311. Log_Write_NKF4(2, LOG_XKF14_MSG, time_us);
  312. Log_Write_Quaternion(2, LOG_XKQ3_MSG, time_us);
  313. }
  314. // write range beacon fusion debug packet if the range value is non-zero
  315. Log_Write_Beacon(time_us);
  316. // write debug data for body frame odometry fusion
  317. Log_Write_BodyOdom(time_us);
  318. // log state variances every 0.49s
  319. Log_Write_State_Variances(time_us);
  320. // log EKF timing statistics every 5s
  321. static uint32_t lastTimingLogTime_ms = 0;
  322. if (AP_HAL::millis() - lastTimingLogTime_ms > 5000) {
  323. lastTimingLogTime_ms = AP_HAL::millis();
  324. struct ekf_timing timing;
  325. for (uint8_t i=0; i<activeCores(); i++) {
  326. getTimingStatistics(i, timing);
  327. if (i == 0) {
  328. Log_EKF_Timing("XKT1", time_us, timing);
  329. } else if (i == 1) {
  330. Log_EKF_Timing("XKT2", time_us, timing);
  331. } else if (i == 2) {
  332. Log_EKF_Timing("XKT3", time_us, timing);
  333. }
  334. }
  335. }
  336. }