AP_NavEKF2_Logging.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  1. #include "AP_NavEKF2.h"
  2. #include <AP_HAL/HAL.h>
  3. #include <AP_Logger/AP_Logger.h>
  4. void NavEKF2::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 NavEKF2::Log_Write_NKF2(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  44. {
  45. // Write second EKF packet
  46. float azbias = 0;
  47. Vector3f wind;
  48. Vector3f magNED;
  49. Vector3f magXYZ;
  50. Vector3f gyroScaleFactor;
  51. uint8_t magIndex = getActiveMag(_core);
  52. getAccelZBias(_core,azbias);
  53. getWind(_core,wind);
  54. getMagNED(_core,magNED);
  55. getMagXYZ(_core,magXYZ);
  56. getGyroScaleErrorPercentage(_core,gyroScaleFactor);
  57. const struct log_NKF2 pkt2{
  58. LOG_PACKET_HEADER_INIT(msg_id),
  59. time_us : time_us,
  60. AZbias : (int8_t)(100*azbias),
  61. scaleX : (int16_t)(100*gyroScaleFactor.x),
  62. scaleY : (int16_t)(100*gyroScaleFactor.y),
  63. scaleZ : (int16_t)(100*gyroScaleFactor.z),
  64. windN : (int16_t)(100*wind.x),
  65. windE : (int16_t)(100*wind.y),
  66. magN : (int16_t)(magNED.x),
  67. magE : (int16_t)(magNED.y),
  68. magD : (int16_t)(magNED.z),
  69. magX : (int16_t)(magXYZ.x),
  70. magY : (int16_t)(magXYZ.y),
  71. magZ : (int16_t)(magXYZ.z),
  72. index : (uint8_t)(magIndex)
  73. };
  74. AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
  75. }
  76. void NavEKF2::Log_Write_NKF3(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  77. {
  78. // Write third EKF packet
  79. Vector3f velInnov;
  80. Vector3f posInnov;
  81. Vector3f magInnov;
  82. float tasInnov = 0;
  83. float yawInnov = 0;
  84. getInnovations(_core,velInnov, posInnov, magInnov, tasInnov, yawInnov);
  85. const struct log_NKF3 pkt3{
  86. LOG_PACKET_HEADER_INIT(msg_id),
  87. time_us : time_us,
  88. innovVN : (int16_t)(100*velInnov.x),
  89. innovVE : (int16_t)(100*velInnov.y),
  90. innovVD : (int16_t)(100*velInnov.z),
  91. innovPN : (int16_t)(100*posInnov.x),
  92. innovPE : (int16_t)(100*posInnov.y),
  93. innovPD : (int16_t)(100*posInnov.z),
  94. innovMX : (int16_t)(magInnov.x),
  95. innovMY : (int16_t)(magInnov.y),
  96. innovMZ : (int16_t)(magInnov.z),
  97. innovYaw : (int16_t)(100*degrees(yawInnov)),
  98. innovVT : (int16_t)(100*tasInnov)
  99. };
  100. AP::logger().WriteBlock(&pkt3, sizeof(pkt3));
  101. }
  102. void NavEKF2::Log_Write_NKF4(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  103. {
  104. // Write fourth EKF packet
  105. float velVar = 0;
  106. float posVar = 0;
  107. float hgtVar = 0;
  108. Vector3f magVar;
  109. float tasVar = 0;
  110. Vector2f offset;
  111. uint16_t faultStatus=0;
  112. uint8_t timeoutStatus=0;
  113. nav_filter_status solutionStatus {};
  114. nav_gps_status gpsStatus {};
  115. getVariances(_core,velVar, posVar, hgtVar, magVar, tasVar, offset);
  116. float tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
  117. getFilterFaults(_core,faultStatus);
  118. getFilterTimeouts(_core,timeoutStatus);
  119. getFilterStatus(_core,solutionStatus);
  120. getFilterGpsStatus(_core,gpsStatus);
  121. float tiltError;
  122. getTiltError(_core,tiltError);
  123. int8_t primaryIndex = getPrimaryCoreIndex();
  124. const struct log_NKF4 pkt4{
  125. LOG_PACKET_HEADER_INIT(msg_id),
  126. time_us : time_us,
  127. sqrtvarV : (int16_t)(100*velVar),
  128. sqrtvarP : (int16_t)(100*posVar),
  129. sqrtvarH : (int16_t)(100*hgtVar),
  130. sqrtvarM : (int16_t)(100*tempVar),
  131. sqrtvarVT : (int16_t)(100*tasVar),
  132. tiltErr : (float)tiltError,
  133. offsetNorth : (int8_t)(offset.x),
  134. offsetEast : (int8_t)(offset.y),
  135. faults : (uint16_t)(faultStatus),
  136. timeouts : (uint8_t)(timeoutStatus),
  137. solution : (uint16_t)(solutionStatus.value),
  138. gps : (uint16_t)(gpsStatus.value),
  139. primary : (int8_t)primaryIndex
  140. };
  141. AP::logger().WriteBlock(&pkt4, sizeof(pkt4));
  142. }
  143. void NavEKF2::Log_Write_NKF5(uint64_t time_us) const
  144. {
  145. // Write fifth EKF packet - take data from the primary instance
  146. float normInnov=0; // normalised innovation variance ratio for optical flow observations fused by the main nav filter
  147. float gndOffset=0; // estimated vertical position of the terrain relative to the nav filter zero datum
  148. float flowInnovX=0, flowInnovY=0; // optical flow LOS rate vector innovations from the main nav filter
  149. float auxFlowInnov=0; // optical flow LOS rate innovation from terrain offset estimator
  150. float HAGL=0; // height above ground level
  151. float rngInnov=0; // range finder innovations
  152. float range=0; // measured range
  153. float gndOffsetErr=0; // filter ground offset state error
  154. Vector3f predictorErrors; // output predictor angle, velocity and position tracking error
  155. getFlowDebug(-1,normInnov, gndOffset, flowInnovX, flowInnovY, auxFlowInnov, HAGL, rngInnov, range, gndOffsetErr);
  156. getOutputTrackingError(-1,predictorErrors);
  157. const struct log_NKF5 pkt5{
  158. LOG_PACKET_HEADER_INIT(LOG_NKF5_MSG),
  159. time_us : time_us,
  160. normInnov : (uint8_t)(MIN(100*normInnov,255)),
  161. FIX : (int16_t)(1000*flowInnovX),
  162. FIY : (int16_t)(1000*flowInnovY),
  163. AFI : (int16_t)(1000*auxFlowInnov),
  164. HAGL : (int16_t)(100*HAGL),
  165. offset : (int16_t)(100*gndOffset),
  166. RI : (int16_t)(100*rngInnov),
  167. meaRng : (uint16_t)(100*range),
  168. errHAGL : (uint16_t)(100*gndOffsetErr),
  169. angErr : (float)predictorErrors.x,
  170. velErr : (float)predictorErrors.y,
  171. posErr : (float)predictorErrors.z
  172. };
  173. AP::logger().WriteBlock(&pkt5, sizeof(pkt5));
  174. }
  175. void NavEKF2::Log_Write_Quaternion(uint8_t _core, LogMessages msg_id, uint64_t time_us) const
  176. {
  177. // log quaternion
  178. Quaternion quat;
  179. getQuaternion(_core, quat);
  180. const struct log_Quaternion pktq1{
  181. LOG_PACKET_HEADER_INIT(msg_id),
  182. time_us : time_us,
  183. q1 : quat.q1,
  184. q2 : quat.q2,
  185. q3 : quat.q3,
  186. q4 : quat.q4
  187. };
  188. AP::logger().WriteBlock(&pktq1, sizeof(pktq1));
  189. }
  190. void NavEKF2::Log_Write_Beacon(uint64_t time_us) const
  191. {
  192. if (AP::beacon() != nullptr) {
  193. uint8_t ID;
  194. float rng;
  195. float innovVar;
  196. float innov;
  197. float testRatio;
  198. Vector3f beaconPosNED;
  199. float bcnPosOffsetHigh;
  200. float bcnPosOffsetLow;
  201. if (getRangeBeaconDebug(-1, ID, rng, innov, innovVar, testRatio, beaconPosNED, bcnPosOffsetHigh, bcnPosOffsetLow)) {
  202. if (rng > 0.0f) {
  203. struct log_RngBcnDebug pkt10 = {
  204. LOG_PACKET_HEADER_INIT(LOG_NKF10_MSG),
  205. time_us : time_us,
  206. ID : (uint8_t)ID,
  207. rng : (int16_t)(100*rng),
  208. innov : (int16_t)(100*innov),
  209. sqrtInnovVar : (uint16_t)(100*safe_sqrt(innovVar)),
  210. testRatio : (uint16_t)(100*constrain_float(testRatio,0.0f,650.0f)),
  211. beaconPosN : (int16_t)(100*beaconPosNED.x),
  212. beaconPosE : (int16_t)(100*beaconPosNED.y),
  213. beaconPosD : (int16_t)(100*beaconPosNED.z),
  214. offsetHigh : (int16_t)(100*bcnPosOffsetHigh),
  215. offsetLow : (int16_t)(100*bcnPosOffsetLow),
  216. posN : 0,
  217. posE : 0,
  218. posD : 0
  219. };
  220. AP::logger().WriteBlock(&pkt10, sizeof(pkt10));
  221. }
  222. }
  223. }
  224. }
  225. void NavEKF2::Log_Write()
  226. {
  227. // only log if enabled
  228. if (activeCores() <= 0) {
  229. return;
  230. }
  231. const uint64_t time_us = AP_HAL::micros64();
  232. Log_Write_EKF1(0, LOG_NKF1_MSG, time_us);
  233. Log_Write_NKF2(0, LOG_NKF2_MSG, time_us);
  234. Log_Write_NKF3(0, LOG_NKF3_MSG, time_us);
  235. Log_Write_NKF4(0, LOG_NKF4_MSG, time_us);
  236. Log_Write_NKF5(time_us);
  237. Log_Write_Quaternion(0, LOG_NKQ1_MSG, time_us);
  238. // log EKF state info for the second EFK core if enabled
  239. if (activeCores() >= 2) {
  240. Log_Write_EKF1(1, LOG_NKF6_MSG, time_us);
  241. Log_Write_NKF2(1, LOG_NKF7_MSG, time_us);
  242. Log_Write_NKF3(1, LOG_NKF8_MSG, time_us);
  243. Log_Write_NKF4(1, LOG_NKF9_MSG, time_us);
  244. Log_Write_Quaternion(1, LOG_NKQ2_MSG, time_us);
  245. }
  246. // log EKF state info for the third EFK core if enabled
  247. if (activeCores() >= 3) {
  248. Log_Write_EKF1(2, LOG_NKF11_MSG, time_us);
  249. Log_Write_NKF2(2, LOG_NKF12_MSG, time_us);
  250. Log_Write_NKF3(2, LOG_NKF13_MSG, time_us);
  251. Log_Write_NKF4(2, LOG_NKF14_MSG, time_us);
  252. Log_Write_Quaternion(2, LOG_NKQ3_MSG, time_us);
  253. }
  254. // write range beacon fusion debug packet if the range value is non-zero
  255. Log_Write_Beacon(time_us);
  256. // log EKF timing statistics every 5s
  257. static uint32_t lastTimingLogTime_ms = 0;
  258. if (AP_HAL::millis() - lastTimingLogTime_ms > 5000) {
  259. lastTimingLogTime_ms = AP_HAL::millis();
  260. struct ekf_timing timing;
  261. for (uint8_t i=0; i<activeCores(); i++) {
  262. getTimingStatistics(i, timing);
  263. if (i == 0) {
  264. Log_EKF_Timing("NKT1", time_us, timing);
  265. } else if (i == 1) {
  266. Log_EKF_Timing("NKT2", time_us, timing);
  267. } else if (i == 2) {
  268. Log_EKF_Timing("NKT3", time_us, timing);
  269. }
  270. }
  271. }
  272. }