Log.cpp 9.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305
  1. #include "Sub.h"
  2. #if LOGGING_ENABLED == ENABLED
  3. // Code to Write and Read packets from AP_Logger log memory
  4. // Code to interact with the user to dump or erase logs
  5. struct PACKED log_Control_Tuning {
  6. LOG_PACKET_HEADER;
  7. uint64_t time_us;
  8. float throttle_in;
  9. float angle_boost;
  10. float throttle_out;
  11. float throttle_hover;
  12. float desired_alt;
  13. float inav_alt;
  14. float baro_alt;
  15. int16_t desired_rangefinder_alt;
  16. int16_t rangefinder_alt;
  17. float terr_alt;
  18. int16_t target_climb_rate;
  19. int16_t climb_rate;
  20. };
  21. // Write a control tuning packet
  22. void Sub::Log_Write_Control_Tuning()
  23. {
  24. // get terrain altitude
  25. float terr_alt = 0.0f;
  26. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  27. terrain.height_above_terrain(terr_alt, true);
  28. #endif
  29. struct log_Control_Tuning pkt = {
  30. LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
  31. time_us : AP_HAL::micros64(),
  32. throttle_in : attitude_control.get_throttle_in(),
  33. angle_boost : attitude_control.angle_boost(),
  34. throttle_out : motors.get_throttle(),
  35. throttle_hover : motors.get_throttle_hover(),
  36. desired_alt : pos_control.get_alt_target() / 100.0f,
  37. inav_alt : inertial_nav.get_altitude() / 100.0f,
  38. baro_alt : barometer.get_altitude(),
  39. desired_rangefinder_alt : (int16_t)target_rangefinder_alt,
  40. rangefinder_alt : rangefinder_state.alt_cm,
  41. terr_alt : terr_alt,
  42. target_climb_rate : (int16_t)pos_control.get_vel_target_z(),
  43. climb_rate : climb_rate
  44. };
  45. logger.WriteBlock(&pkt, sizeof(pkt));
  46. }
  47. // Write an attitude packet
  48. void Sub::Log_Write_Attitude()
  49. {
  50. Vector3f targets = attitude_control.get_att_target_euler_cd();
  51. targets.z = wrap_360_cd(targets.z);
  52. logger.Write_Attitude(ahrs, targets);
  53. AP::ahrs_navekf().Log_Write();
  54. logger.Write_AHRS2(ahrs);
  55. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  56. sitl.Log_Write_SIMSTATE();
  57. #endif
  58. logger.Write_POS(ahrs);
  59. }
  60. struct PACKED log_MotBatt {
  61. LOG_PACKET_HEADER;
  62. uint64_t time_us;
  63. float lift_max;
  64. float bat_volt;
  65. float bat_res;
  66. float th_limit;
  67. };
  68. // Write an rate packet
  69. void Sub::Log_Write_MotBatt()
  70. {
  71. struct log_MotBatt pkt_mot = {
  72. LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
  73. time_us : AP_HAL::micros64(),
  74. lift_max : (float)(motors.get_lift_max()),
  75. bat_volt : (float)(motors.get_batt_voltage_filt()),
  76. bat_res : (float)(battery.get_resistance()),
  77. th_limit : (float)(motors.get_throttle_limit())
  78. };
  79. logger.WriteBlock(&pkt_mot, sizeof(pkt_mot));
  80. }
  81. // Wrote an event packet
  82. void Sub::Log_Write_Event(Log_Event id)
  83. {
  84. logger.Write_Event(id);
  85. }
  86. struct PACKED log_Data_Int16t {
  87. LOG_PACKET_HEADER;
  88. uint64_t time_us;
  89. uint8_t id;
  90. int16_t data_value;
  91. };
  92. // Write an int16_t data packet
  93. UNUSED_FUNCTION
  94. void Sub::Log_Write_Data(uint8_t id, int16_t value)
  95. {
  96. if (should_log(MASK_LOG_ANY)) {
  97. struct log_Data_Int16t pkt = {
  98. LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
  99. time_us : AP_HAL::micros64(),
  100. id : id,
  101. data_value : value
  102. };
  103. logger.WriteCriticalBlock(&pkt, sizeof(pkt));
  104. }
  105. }
  106. struct PACKED log_Data_UInt16t {
  107. LOG_PACKET_HEADER;
  108. uint64_t time_us;
  109. uint8_t id;
  110. uint16_t data_value;
  111. };
  112. // Write an uint16_t data packet
  113. UNUSED_FUNCTION
  114. void Sub::Log_Write_Data(uint8_t id, uint16_t value)
  115. {
  116. if (should_log(MASK_LOG_ANY)) {
  117. struct log_Data_UInt16t pkt = {
  118. LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
  119. time_us : AP_HAL::micros64(),
  120. id : id,
  121. data_value : value
  122. };
  123. logger.WriteCriticalBlock(&pkt, sizeof(pkt));
  124. }
  125. }
  126. struct PACKED log_Data_Int32t {
  127. LOG_PACKET_HEADER;
  128. uint64_t time_us;
  129. uint8_t id;
  130. int32_t data_value;
  131. };
  132. // Write an int32_t data packet
  133. void Sub::Log_Write_Data(uint8_t id, int32_t value)
  134. {
  135. if (should_log(MASK_LOG_ANY)) {
  136. struct log_Data_Int32t pkt = {
  137. LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
  138. time_us : AP_HAL::micros64(),
  139. id : id,
  140. data_value : value
  141. };
  142. logger.WriteCriticalBlock(&pkt, sizeof(pkt));
  143. }
  144. }
  145. struct PACKED log_Data_UInt32t {
  146. LOG_PACKET_HEADER;
  147. uint64_t time_us;
  148. uint8_t id;
  149. uint32_t data_value;
  150. };
  151. // Write a uint32_t data packet
  152. void Sub::Log_Write_Data(uint8_t id, uint32_t value)
  153. {
  154. if (should_log(MASK_LOG_ANY)) {
  155. struct log_Data_UInt32t pkt = {
  156. LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
  157. time_us : AP_HAL::micros64(),
  158. id : id,
  159. data_value : value
  160. };
  161. logger.WriteCriticalBlock(&pkt, sizeof(pkt));
  162. }
  163. }
  164. struct PACKED log_Data_Float {
  165. LOG_PACKET_HEADER;
  166. uint64_t time_us;
  167. uint8_t id;
  168. float data_value;
  169. };
  170. // Write a float data packet
  171. UNUSED_FUNCTION
  172. void Sub::Log_Write_Data(uint8_t id, float value)
  173. {
  174. if (should_log(MASK_LOG_ANY)) {
  175. struct log_Data_Float pkt = {
  176. LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
  177. time_us : AP_HAL::micros64(),
  178. id : id,
  179. data_value : value
  180. };
  181. logger.WriteCriticalBlock(&pkt, sizeof(pkt));
  182. }
  183. }
  184. // logs when baro or compass becomes unhealthy
  185. void Sub::Log_Sensor_Health()
  186. {
  187. // check baro
  188. if (sensor_health.baro != barometer.healthy()) {
  189. sensor_health.baro = barometer.healthy();
  190. AP::logger().Write_Error(LogErrorSubsystem::BARO, (sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
  191. }
  192. // check compass
  193. if (sensor_health.compass != compass.healthy()) {
  194. sensor_health.compass = compass.healthy();
  195. AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
  196. }
  197. }
  198. struct PACKED log_GuidedTarget {
  199. LOG_PACKET_HEADER;
  200. uint64_t time_us;
  201. uint8_t type;
  202. float pos_target_x;
  203. float pos_target_y;
  204. float pos_target_z;
  205. float vel_target_x;
  206. float vel_target_y;
  207. float vel_target_z;
  208. };
  209. // Write a Guided mode target
  210. void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target)
  211. {
  212. struct log_GuidedTarget pkt = {
  213. LOG_PACKET_HEADER_INIT(LOG_GUIDEDTARGET_MSG),
  214. time_us : AP_HAL::micros64(),
  215. type : target_type,
  216. pos_target_x : pos_target.x,
  217. pos_target_y : pos_target.y,
  218. pos_target_z : pos_target.z,
  219. vel_target_x : vel_target.x,
  220. vel_target_y : vel_target.y,
  221. vel_target_z : vel_target.z
  222. };
  223. logger.WriteBlock(&pkt, sizeof(pkt));
  224. }
  225. // type and unit information can be found in
  226. // libraries/AP_Logger/Logstructure.h; search for "log_Units" for
  227. // units and "Format characters" for field type information
  228. const struct LogStructure Sub::log_structure[] = {
  229. LOG_COMMON_STRUCTURES,
  230. { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
  231. "CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
  232. { LOG_MOTBATT_MSG, sizeof(log_MotBatt),
  233. "MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
  234. { LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
  235. "D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
  236. { LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
  237. "DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
  238. { LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
  239. "D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
  240. { LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
  241. "DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
  242. { LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
  243. "DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
  244. { LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
  245. "GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
  246. };
  247. void Sub::Log_Write_Vehicle_Startup_Messages()
  248. {
  249. // only 200(?) bytes are guaranteed by AP_Logger
  250. logger.Write_Mode(control_mode, control_mode_reason);
  251. ahrs.Log_Write_Home_And_Origin();
  252. gps.Write_AP_Logger_Log_Startup_messages();
  253. }
  254. void Sub::log_init()
  255. {
  256. logger.Init(log_structure, ARRAY_SIZE(log_structure));
  257. }
  258. #else // LOGGING_ENABLED
  259. void Sub::Log_Write_Control_Tuning() {}
  260. void Sub::Log_Write_Performance() {}
  261. void Sub::Log_Write_Attitude(void) {}
  262. void Sub::Log_Write_MotBatt() {}
  263. void Sub::Log_Write_Event(Log_Event id) {}
  264. void Sub::Log_Write_Data(uint8_t id, int32_t value) {}
  265. void Sub::Log_Write_Data(uint8_t id, uint32_t value) {}
  266. void Sub::Log_Write_Data(uint8_t id, int16_t value) {}
  267. void Sub::Log_Write_Data(uint8_t id, uint16_t value) {}
  268. void Sub::Log_Write_Data(uint8_t id, float value) {}
  269. void Sub::Log_Sensor_Health() {}
  270. void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
  271. void Sub::Log_Write_Vehicle_Startup_Messages() {}
  272. void Sub::log_init(void) {}
  273. #endif // LOGGING_ENABLED