AP_Logger.cpp 37 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200
  1. #include "AP_Logger.h"
  2. #include "AP_Logger_Backend.h"
  3. #include "AP_Logger_File.h"
  4. #include "AP_Logger_SITL.h"
  5. #include "AP_Logger_DataFlash.h"
  6. #include "AP_Logger_MAVLink.h"
  7. #include <AP_InternalError/AP_InternalError.h>
  8. #include <GCS_MAVLink/GCS.h>
  9. AP_Logger *AP_Logger::_singleton;
  10. extern const AP_HAL::HAL& hal;
  11. #ifndef HAL_LOGGING_FILE_BUFSIZE
  12. #if HAL_MEM_CLASS >= HAL_MEM_CLASS_300
  13. #define HAL_LOGGING_FILE_BUFSIZE 50
  14. #else
  15. #define HAL_LOGGING_FILE_BUFSIZE 16
  16. #endif
  17. #endif
  18. #ifndef HAL_LOGGING_MAV_BUFSIZE
  19. #define HAL_LOGGING_MAV_BUFSIZE 8
  20. #endif
  21. #ifndef HAL_LOGGING_FILE_TIMEOUT
  22. #define HAL_LOGGING_FILE_TIMEOUT 5
  23. #endif
  24. // by default log for 15 seconds after disarming
  25. #ifndef HAL_LOGGER_ARM_PERSIST
  26. #define HAL_LOGGER_ARM_PERSIST 15
  27. #endif
  28. #ifndef HAL_LOGGING_BACKENDS_DEFAULT
  29. # ifdef HAL_LOGGING_DATAFLASH
  30. # define HAL_LOGGING_BACKENDS_DEFAULT Backend_Type::BLOCK
  31. # else
  32. # define HAL_LOGGING_BACKENDS_DEFAULT Backend_Type::FILESYSTEM
  33. # endif
  34. #endif
  35. const AP_Param::GroupInfo AP_Logger::var_info[] = {
  36. // @Param: _BACKEND_TYPE
  37. // @DisplayName: AP_Logger Backend Storage type
  38. // @Description: Bitmap of what Logger backend types to enable. Block-based logging is available on SITL and boards with dataflash chips. Multiple backends can be selected.
  39. // @Values: 0:None,1:File,2:MAVLink,3:File and MAVLink,4:Block,6:Block and MAVLink
  40. // @Bitmask: 0:File,1:MAVLink,2:Block
  41. // @User: Standard
  42. AP_GROUPINFO("_BACKEND_TYPE", 0, AP_Logger, _params.backend_types, uint8_t(HAL_LOGGING_BACKENDS_DEFAULT)),
  43. // @Param: _FILE_BUFSIZE
  44. // @DisplayName: Maximum AP_Logger File Backend buffer size (in kilobytes)
  45. // @Description: The AP_Logger_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
  46. // @User: Standard
  47. AP_GROUPINFO("_FILE_BUFSIZE", 1, AP_Logger, _params.file_bufsize, HAL_LOGGING_FILE_BUFSIZE),
  48. // @Param: _DISARMED
  49. // @DisplayName: Enable logging while disarmed
  50. // @Description: If LOG_DISARMED is set to 1 then logging will be enabled while disarmed. This can make for very large logfiles but can help a lot when tracking down startup issues
  51. // @Values: 0:Disabled,1:Enabled
  52. // @User: Standard
  53. AP_GROUPINFO("_DISARMED", 2, AP_Logger, _params.log_disarmed, 0),
  54. // @Param: _REPLAY
  55. // @DisplayName: Enable logging of information needed for Replay
  56. // @Description: If LOG_REPLAY is set to 1 then the EKF2 state estimator will log detailed information needed for diagnosing problems with the Kalman filter. It is suggested that you also raise LOG_FILE_BUFSIZE to give more buffer space for logging and use a high quality microSD card to ensure no sensor data is lost
  57. // @Values: 0:Disabled,1:Enabled
  58. // @User: Standard
  59. AP_GROUPINFO("_REPLAY", 3, AP_Logger, _params.log_replay, 0),
  60. // @Param: _FILE_DSRMROT
  61. // @DisplayName: Stop logging to current file on disarm
  62. // @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened.
  63. // @Values: 0:Disabled,1:Enabled
  64. // @User: Standard
  65. AP_GROUPINFO("_FILE_DSRMROT", 4, AP_Logger, _params.file_disarm_rot, 0),
  66. // @Param: _MAV_BUFSIZE
  67. // @DisplayName: Maximum AP_Logger MAVLink Backend buffer size
  68. // @Description: Maximum amount of memory to allocate to AP_Logger-over-mavlink
  69. // @User: Advanced
  70. // @Units: kB
  71. AP_GROUPINFO("_MAV_BUFSIZE", 5, AP_Logger, _params.mav_bufsize, HAL_LOGGING_MAV_BUFSIZE),
  72. // @Param: _FILE_TIMEOUT
  73. // @DisplayName: Timeout before giving up on file writes
  74. // @Description: This controls the amount of time before failing writes to a log file cause the file to be closed and logging stopped.
  75. // @User: Standard
  76. // @Units: s
  77. AP_GROUPINFO("_FILE_TIMEOUT", 6, AP_Logger, _params.file_timeout, HAL_LOGGING_FILE_TIMEOUT),
  78. AP_GROUPEND
  79. };
  80. #define streq(x, y) (!strcmp(x, y))
  81. AP_Logger::AP_Logger(const AP_Int32 &log_bitmask)
  82. : _log_bitmask(log_bitmask)
  83. {
  84. AP_Param::setup_object_defaults(this, var_info);
  85. if (_singleton != nullptr) {
  86. AP_HAL::panic("AP_Logger must be singleton");
  87. }
  88. _singleton = this;
  89. }
  90. void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
  91. {
  92. gcs().send_text(MAV_SEVERITY_INFO, "Preparing log system");
  93. if (hal.util->was_watchdog_armed()) {
  94. gcs().send_text(MAV_SEVERITY_INFO, "Forcing logging for watchdog reset");
  95. _params.log_disarmed.set(1);
  96. }
  97. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  98. validate_structures(structures, num_types);
  99. dump_structures(structures, num_types);
  100. #endif
  101. if (_next_backend == LOGGER_MAX_BACKENDS) {
  102. AP_HAL::panic("Too many backends");
  103. return;
  104. }
  105. _num_types = num_types;
  106. _structures = structures;
  107. #if defined(HAL_BOARD_LOG_DIRECTORY) && HAVE_FILESYSTEM_SUPPORT
  108. if (_params.backend_types & uint8_t(Backend_Type::FILESYSTEM)) {
  109. LoggerMessageWriter_DFLogStart *message_writer =
  110. new LoggerMessageWriter_DFLogStart();
  111. if (message_writer != nullptr) {
  112. backends[_next_backend] = new AP_Logger_File(*this,
  113. message_writer,
  114. HAL_BOARD_LOG_DIRECTORY);
  115. }
  116. if (backends[_next_backend] == nullptr) {
  117. hal.console->printf("Unable to open AP_Logger_File");
  118. } else {
  119. _next_backend++;
  120. }
  121. }
  122. #endif // HAVE_FILESYSTEM_SUPPORT
  123. #if LOGGER_MAVLINK_SUPPORT
  124. if (_params.backend_types & uint8_t(Backend_Type::MAVLINK)) {
  125. if (_next_backend == LOGGER_MAX_BACKENDS) {
  126. AP_HAL::panic("Too many backends");
  127. return;
  128. }
  129. LoggerMessageWriter_DFLogStart *message_writer =
  130. new LoggerMessageWriter_DFLogStart();
  131. if (message_writer != nullptr) {
  132. backends[_next_backend] = new AP_Logger_MAVLink(*this,
  133. message_writer);
  134. }
  135. if (backends[_next_backend] == nullptr) {
  136. hal.console->printf("Unable to open AP_Logger_MAVLink");
  137. } else {
  138. _next_backend++;
  139. }
  140. }
  141. #endif
  142. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  143. if (_params.backend_types & uint8_t(Backend_Type::BLOCK)) {
  144. if (_next_backend == LOGGER_MAX_BACKENDS) {
  145. AP_HAL::panic("Too many backends");
  146. return;
  147. }
  148. LoggerMessageWriter_DFLogStart *message_writer =
  149. new LoggerMessageWriter_DFLogStart();
  150. if (message_writer != nullptr) {
  151. backends[_next_backend] = new AP_Logger_SITL(*this, message_writer);
  152. }
  153. if (backends[_next_backend] == nullptr) {
  154. hal.console->printf("Unable to open AP_Logger_SITL");
  155. } else {
  156. _next_backend++;
  157. }
  158. }
  159. #endif
  160. #ifdef HAL_LOGGING_DATAFLASH
  161. if (_params.backend_types & uint8_t(Backend_Type::BLOCK)) {
  162. if (_next_backend == LOGGER_MAX_BACKENDS) {
  163. AP_HAL::panic("Too many backends");
  164. return;
  165. }
  166. LoggerMessageWriter_DFLogStart *message_writer =
  167. new LoggerMessageWriter_DFLogStart();
  168. if (message_writer != nullptr) {
  169. backends[_next_backend] = new AP_Logger_DataFlash(*this, message_writer);
  170. }
  171. if (backends[_next_backend] == nullptr) {
  172. hal.console->printf("Unable to open AP_Logger_DataFlash");
  173. } else {
  174. _next_backend++;
  175. }
  176. }
  177. #endif
  178. for (uint8_t i=0; i<_next_backend; i++) {
  179. backends[i]->Init();
  180. }
  181. Prep();
  182. EnableWrites(true);
  183. gcs().send_text(MAV_SEVERITY_INFO, "Prepared log system");
  184. }
  185. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  186. #include <stdio.h>
  187. #define DEBUG_LOG_STRUCTURES 0
  188. extern const AP_HAL::HAL& hal;
  189. #define Debug(fmt, args ...) do {::fprintf(stderr, "%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  190. /// return the number of commas present in string
  191. static uint8_t count_commas(const char *string)
  192. {
  193. uint8_t ret = 0;
  194. for (uint8_t i=0; i<strlen(string); i++) {
  195. if (string[i] == ',') {
  196. ret++;
  197. }
  198. }
  199. return ret;
  200. }
  201. /// return a unit name given its ID
  202. const char* AP_Logger::unit_name(const uint8_t unit_id)
  203. {
  204. for(uint8_t i=0; i<unit_id; i++) {
  205. if (_units[i].ID == unit_id) {
  206. return _units[i].unit;
  207. }
  208. }
  209. return NULL;
  210. }
  211. /// return a multiplier value given its ID
  212. double AP_Logger::multiplier_name(const uint8_t multiplier_id)
  213. {
  214. for(uint8_t i=0; i<multiplier_id; i++) {
  215. if (_multipliers[i].ID == multiplier_id) {
  216. return _multipliers[i].multiplier;
  217. }
  218. }
  219. // Should we abort here?
  220. return 1.0f;
  221. }
  222. /// pretty-print field information from a log structure
  223. void AP_Logger::dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
  224. {
  225. ::fprintf(stderr, " %s (%s)*(%f)\n", label, unit_name(logstructure->units[fieldnum]), multiplier_name(logstructure->multipliers[fieldnum]));
  226. }
  227. /// pretty-print log structures
  228. /// @note structures MUST be well-formed
  229. void AP_Logger::dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
  230. {
  231. #if DEBUG_LOG_STRUCTURES
  232. for (uint16_t i=0; i<num_types; i++) {
  233. const struct LogStructure *logstructure = &logstructures[i];
  234. ::fprintf(stderr, "%s\n", logstructure->name);
  235. char label[32] = { };
  236. uint8_t labeloffset = 0;
  237. int8_t fieldnum = 0;
  238. for (uint8_t j=0; j<strlen(logstructure->labels); j++) {
  239. char labelchar = logstructure->labels[j];
  240. if (labelchar == '\0') {
  241. break;
  242. }
  243. if (labelchar == ',') {
  244. dump_structure_field(logstructure, label, fieldnum);
  245. fieldnum++;
  246. labeloffset = 0;
  247. memset(label, '\0', 32);
  248. } else {
  249. label[labeloffset++] = labelchar;
  250. }
  251. }
  252. dump_structure_field(logstructure, label, fieldnum);
  253. ::fprintf(stderr, "\n"); // just add a CR to the output
  254. }
  255. #endif
  256. }
  257. bool AP_Logger::validate_structure(const struct LogStructure *logstructure, const int16_t offset)
  258. {
  259. bool passed = true;
  260. #if DEBUG_LOG_STRUCTURES
  261. Debug("offset=%d ID=%d NAME=%s", offset, logstructure->msg_type, logstructure->name);
  262. #endif
  263. // fields must be null-terminated
  264. #define CHECK_ENTRY(fieldname,fieldname_s,fieldlen) \
  265. do { \
  266. if (strnlen(logstructure->fieldname, fieldlen) > fieldlen-1) { \
  267. Debug(" Message " fieldname_s " not NULL-terminated or too long"); \
  268. passed = false; \
  269. } \
  270. } while (false)
  271. CHECK_ENTRY(name, "name", LS_NAME_SIZE);
  272. CHECK_ENTRY(format, "format", LS_FORMAT_SIZE);
  273. CHECK_ENTRY(labels, "labels", LS_LABELS_SIZE);
  274. CHECK_ENTRY(units, "units", LS_UNITS_SIZE);
  275. CHECK_ENTRY(multipliers, "multipliers", LS_MULTIPLIERS_SIZE);
  276. #undef CHECK_ENTRY
  277. // ensure each message ID is only used once
  278. if (seen_ids[logstructure->msg_type]) {
  279. Debug(" ID %d used twice (LogStructure offset=%d)", logstructure->msg_type, offset);
  280. passed = false;
  281. }
  282. seen_ids[logstructure->msg_type] = true;
  283. // ensure we have enough labels to cover columns
  284. uint8_t fieldcount = strlen(logstructure->format);
  285. uint8_t labelcount = count_commas(logstructure->labels)+1;
  286. if (fieldcount != labelcount) {
  287. Debug(" fieldcount=%u does not match labelcount=%u",
  288. fieldcount, labelcount);
  289. passed = false;
  290. }
  291. // check that the structure is of an appropriate length to take fields
  292. const int16_t msg_len = Write_calc_msg_len(logstructure->format);
  293. if (msg_len != logstructure->msg_len) {
  294. Debug(" Calculated message length for (%s) based on format field (%s) does not match structure size (%d != %u)", logstructure->name, logstructure->format, msg_len, logstructure->msg_len);
  295. passed = false;
  296. }
  297. // ensure we have units for each field:
  298. if (strlen(logstructure->units) != fieldcount) {
  299. Debug(" fieldcount=%u does not match unitcount=%u",
  300. (unsigned)fieldcount, (unsigned)strlen(logstructure->units));
  301. passed = false;
  302. }
  303. // ensure we have multipliers for each field
  304. if (strlen(logstructure->multipliers) != fieldcount) {
  305. Debug(" fieldcount=%u does not match multipliercount=%u",
  306. (unsigned)fieldcount, (unsigned)strlen(logstructure->multipliers));
  307. passed = false;
  308. }
  309. // ensure the FMTU messages reference valid units
  310. for (uint8_t j=0; j<strlen(logstructure->units); j++) {
  311. char logunit = logstructure->units[j];
  312. uint8_t k;
  313. for (k=0; k<_num_units; k++) {
  314. if (logunit == _units[k].ID) {
  315. // found this one
  316. break;
  317. }
  318. }
  319. if (k == _num_units) {
  320. Debug(" invalid unit=%c", logunit);
  321. passed = false;
  322. }
  323. }
  324. // ensure the FMTU messages reference valid multipliers
  325. for (uint8_t j=0; j<strlen(logstructure->multipliers); j++) {
  326. char logmultiplier = logstructure->multipliers[j];
  327. uint8_t k;
  328. for (k=0; k<_num_multipliers; k++) {
  329. if (logmultiplier == _multipliers[k].ID) {
  330. // found this one
  331. break;
  332. }
  333. }
  334. if (k == _num_multipliers) {
  335. Debug(" invalid multiplier=%c", logmultiplier);
  336. passed = false;
  337. }
  338. }
  339. // ensure any float has a multiplier of zero
  340. if (false && passed) {
  341. for (uint8_t j=0; j<strlen(logstructure->multipliers); j++) {
  342. const char fmt = logstructure->format[j];
  343. if (fmt != 'f') {
  344. continue;
  345. }
  346. const char logmultiplier = logstructure->multipliers[j];
  347. if (logmultiplier == '0' ||
  348. logmultiplier == '?' ||
  349. logmultiplier == '-') {
  350. continue;
  351. }
  352. Debug(" %s[%u] float with non-zero multiplier=%c",
  353. logstructure->name,
  354. j,
  355. logmultiplier);
  356. passed = false;
  357. }
  358. }
  359. return passed;
  360. }
  361. void AP_Logger::validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
  362. {
  363. Debug("Validating structures");
  364. bool passed = true;
  365. for (uint16_t i=0; i<num_types; i++) {
  366. const struct LogStructure *logstructure = &logstructures[i];
  367. passed = validate_structure(logstructure, i) && passed;
  368. }
  369. // ensure units are unique:
  370. for (uint16_t i=0; i<ARRAY_SIZE(log_Units); i++) {
  371. const struct UnitStructure &a = log_Units[i];
  372. for (uint16_t j=i+1; j<ARRAY_SIZE(log_Units); j++) {
  373. const struct UnitStructure &b = log_Units[j];
  374. if (a.ID == b.ID) {
  375. Debug("duplicate unit id=%c (%s/%s)", a.ID, a.unit, b.unit);
  376. passed = false;
  377. }
  378. if (streq(a.unit, b.unit)) {
  379. Debug("duplicate unit=%s (%c/%c)", a.unit, a.ID, b.ID);
  380. passed = false;
  381. }
  382. }
  383. }
  384. // ensure multipliers are unique:
  385. for (uint16_t i=0; i<ARRAY_SIZE(log_Multipliers); i++) {
  386. const struct MultiplierStructure &a = log_Multipliers[i];
  387. for (uint16_t j=i+1; j<ARRAY_SIZE(log_Multipliers); j++) {
  388. const struct MultiplierStructure &b = log_Multipliers[j];
  389. if (a.ID == b.ID) {
  390. Debug("duplicate multiplier id=%c (%f/%f)",
  391. a.ID, a.multiplier, b.multiplier);
  392. passed = false;
  393. }
  394. if (is_equal(a.multiplier, b.multiplier)) {
  395. if (a.ID == '?' && b.ID == '0') {
  396. // special case
  397. continue;
  398. }
  399. Debug("duplicate multiplier=%f (%c/%c)",
  400. a.multiplier, a.ID, b.ID);
  401. passed = false;
  402. }
  403. }
  404. }
  405. if (!passed) {
  406. Debug("Log structures are invalid");
  407. abort();
  408. }
  409. }
  410. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
  411. const struct LogStructure *AP_Logger::structure(uint16_t num) const
  412. {
  413. return &_structures[num];
  414. }
  415. bool AP_Logger::logging_present() const
  416. {
  417. return _next_backend != 0;
  418. }
  419. bool AP_Logger::logging_enabled() const
  420. {
  421. if (_next_backend == 0) {
  422. return false;
  423. }
  424. for (uint8_t i=0; i<_next_backend; i++) {
  425. if (backends[i]->logging_enabled()) {
  426. return true;
  427. }
  428. }
  429. return false;
  430. }
  431. bool AP_Logger::logging_failed() const
  432. {
  433. if (_next_backend < 1) {
  434. // we should not have been called!
  435. return true;
  436. }
  437. for (uint8_t i=0; i<_next_backend; i++) {
  438. if (backends[i]->logging_failed()) {
  439. return true;
  440. }
  441. }
  442. return false;
  443. }
  444. void AP_Logger::Write_MessageF(const char *fmt, ...)
  445. {
  446. char msg[65] {}; // sizeof(log_Message.msg) + null-termination
  447. va_list ap;
  448. va_start(ap, fmt);
  449. hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
  450. va_end(ap);
  451. Write_Message(msg);
  452. }
  453. void AP_Logger::backend_starting_new_log(const AP_Logger_Backend *backend)
  454. {
  455. for (uint8_t i=0; i<_next_backend; i++) {
  456. if (backends[i] == backend) { // pointer comparison!
  457. // reset sent masks
  458. for (struct log_write_fmt *f = log_write_fmts; f; f=f->next) {
  459. f->sent_mask &= ~(1<<i);
  460. }
  461. break;
  462. }
  463. }
  464. }
  465. bool AP_Logger::should_log(const uint32_t mask) const
  466. {
  467. bool armed = vehicle_is_armed();
  468. if (!(mask & _log_bitmask)) {
  469. return false;
  470. }
  471. if (!armed && !log_while_disarmed()) {
  472. return false;
  473. }
  474. if (in_log_download()) {
  475. return false;
  476. }
  477. if (_next_backend == 0) {
  478. return false;
  479. }
  480. return true;
  481. }
  482. const struct UnitStructure *AP_Logger::unit(uint16_t num) const
  483. {
  484. return &_units[num];
  485. }
  486. const struct MultiplierStructure *AP_Logger::multiplier(uint16_t num) const
  487. {
  488. return &log_Multipliers[num];
  489. }
  490. #define FOR_EACH_BACKEND(methodcall) \
  491. do { \
  492. for (uint8_t i=0; i<_next_backend; i++) { \
  493. backends[i]->methodcall; \
  494. } \
  495. } while (0)
  496. void AP_Logger::PrepForArming()
  497. {
  498. FOR_EACH_BACKEND(PrepForArming());
  499. }
  500. void AP_Logger::setVehicle_Startup_Writer(vehicle_startup_message_Writer writer)
  501. {
  502. _vehicle_messages = writer;
  503. }
  504. void AP_Logger::set_vehicle_armed(const bool armed_state)
  505. {
  506. if (armed_state == _armed) {
  507. // no change in status
  508. return;
  509. }
  510. _armed = armed_state;
  511. if (!_armed) {
  512. // went from armed to disarmed
  513. FOR_EACH_BACKEND(vehicle_was_disarmed());
  514. }
  515. }
  516. // start functions pass straight through to backend:
  517. void AP_Logger::WriteBlock(const void *pBuffer, uint16_t size) {
  518. FOR_EACH_BACKEND(WriteBlock(pBuffer, size));
  519. }
  520. void AP_Logger::WriteCriticalBlock(const void *pBuffer, uint16_t size) {
  521. FOR_EACH_BACKEND(WriteCriticalBlock(pBuffer, size));
  522. }
  523. void AP_Logger::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) {
  524. FOR_EACH_BACKEND(WritePrioritisedBlock(pBuffer, size, is_critical));
  525. }
  526. // change me to "DoTimeConsumingPreparations"?
  527. void AP_Logger::EraseAll() {
  528. FOR_EACH_BACKEND(EraseAll());
  529. }
  530. // change me to "LoggingAvailable"?
  531. bool AP_Logger::CardInserted(void) {
  532. for (uint8_t i=0; i< _next_backend; i++) {
  533. if (backends[i]->CardInserted()) {
  534. return true;
  535. }
  536. }
  537. return false;
  538. }
  539. void AP_Logger::Prep() {
  540. FOR_EACH_BACKEND(Prep());
  541. }
  542. void AP_Logger::StopLogging()
  543. {
  544. FOR_EACH_BACKEND(stop_logging());
  545. }
  546. uint16_t AP_Logger::find_last_log() const {
  547. if (_next_backend == 0) {
  548. return 0;
  549. }
  550. return backends[0]->find_last_log();
  551. }
  552. void AP_Logger::get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) {
  553. if (_next_backend == 0) {
  554. return;
  555. }
  556. backends[0]->get_log_boundaries(log_num, start_page, end_page);
  557. }
  558. void AP_Logger::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) {
  559. if (_next_backend == 0) {
  560. return;
  561. }
  562. backends[0]->get_log_info(log_num, size, time_utc);
  563. }
  564. int16_t AP_Logger::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) {
  565. if (_next_backend == 0) {
  566. return 0;
  567. }
  568. return backends[0]->get_log_data(log_num, page, offset, len, data);
  569. }
  570. uint16_t AP_Logger::get_num_logs(void) {
  571. if (_next_backend == 0) {
  572. return 0;
  573. }
  574. return backends[0]->get_num_logs();
  575. }
  576. /* we're started if any of the backends are started */
  577. bool AP_Logger::logging_started(void) {
  578. for (uint8_t i=0; i< _next_backend; i++) {
  579. if (backends[i]->logging_started()) {
  580. return true;
  581. }
  582. }
  583. return false;
  584. }
  585. void AP_Logger::handle_mavlink_msg(GCS_MAVLINK &link, const mavlink_message_t &msg)
  586. {
  587. switch (msg.msgid) {
  588. case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
  589. FOR_EACH_BACKEND(remote_log_block_status_msg(link.get_chan(), msg));
  590. break;
  591. case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
  592. FALLTHROUGH;
  593. case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
  594. FALLTHROUGH;
  595. case MAVLINK_MSG_ID_LOG_ERASE:
  596. FALLTHROUGH;
  597. case MAVLINK_MSG_ID_LOG_REQUEST_END:
  598. handle_log_message(link, msg);
  599. break;
  600. }
  601. }
  602. void AP_Logger::periodic_tasks() {
  603. handle_log_send();
  604. FOR_EACH_BACKEND(periodic_tasks());
  605. }
  606. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  607. // currently only AP_Logger_File support this:
  608. void AP_Logger::flush(void) {
  609. FOR_EACH_BACKEND(flush());
  610. }
  611. #endif
  612. void AP_Logger::Write_EntireMission()
  613. {
  614. FOR_EACH_BACKEND(Write_EntireMission());
  615. }
  616. void AP_Logger::Write_Message(const char *message)
  617. {
  618. FOR_EACH_BACKEND(Write_Message(message));
  619. }
  620. void AP_Logger::Write_Mode(uint8_t mode, uint8_t reason)
  621. {
  622. FOR_EACH_BACKEND(Write_Mode(mode, reason));
  623. }
  624. void AP_Logger::Write_Parameter(const char *name, float value)
  625. {
  626. FOR_EACH_BACKEND(Write_Parameter(name, value));
  627. }
  628. void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission,
  629. const AP_Mission::Mission_Command &cmd)
  630. {
  631. FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd));
  632. }
  633. void AP_Logger::Write_RallyPoint(uint8_t total,
  634. uint8_t sequence,
  635. const RallyLocation &rally_point)
  636. {
  637. FOR_EACH_BACKEND(Write_RallyPoint(total, sequence, rally_point));
  638. }
  639. void AP_Logger::Write_Rally()
  640. {
  641. FOR_EACH_BACKEND(Write_Rally());
  642. }
  643. uint32_t AP_Logger::num_dropped() const
  644. {
  645. if (_next_backend == 0) {
  646. return 0;
  647. }
  648. return backends[0]->num_dropped();
  649. }
  650. // end functions pass straight through to backend
  651. /* Write support */
  652. void AP_Logger::Write(const char *name, const char *labels, const char *fmt, ...)
  653. {
  654. va_list arg_list;
  655. va_start(arg_list, fmt);
  656. WriteV(name, labels, nullptr, nullptr, fmt, arg_list);
  657. va_end(arg_list);
  658. }
  659. void AP_Logger::Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
  660. {
  661. va_list arg_list;
  662. va_start(arg_list, fmt);
  663. WriteV(name, labels, units, mults, fmt, arg_list);
  664. va_end(arg_list);
  665. }
  666. void AP_Logger::WriteCritical(const char *name, const char *labels, const char *fmt, ...)
  667. {
  668. va_list arg_list;
  669. va_start(arg_list, fmt);
  670. WriteV(name, labels, nullptr, nullptr, fmt, arg_list, true);
  671. va_end(arg_list);
  672. }
  673. void AP_Logger::WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
  674. {
  675. va_list arg_list;
  676. va_start(arg_list, fmt);
  677. WriteV(name, labels, units, mults, fmt, arg_list, true);
  678. va_end(arg_list);
  679. }
  680. void AP_Logger::WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical)
  681. {
  682. struct log_write_fmt *f = msg_fmt_for_name(name, labels, units, mults, fmt);
  683. if (f == nullptr) {
  684. // unable to map name to a messagetype; could be out of
  685. // msgtypes, could be out of slots, ...
  686. AP::internalerror().error(AP_InternalError::error_t::logger_mapfailure);
  687. return;
  688. }
  689. for (uint8_t i=0; i<_next_backend; i++) {
  690. if (!(f->sent_mask & (1U<<i))) {
  691. if (!backends[i]->Write_Emit_FMT(f->msg_type)) {
  692. continue;
  693. }
  694. f->sent_mask |= (1U<<i);
  695. }
  696. va_list arg_copy;
  697. va_copy(arg_copy, arg_list);
  698. backends[i]->Write(f->msg_type, arg_copy, is_critical);
  699. va_end(arg_copy);
  700. }
  701. }
  702. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  703. void AP_Logger::assert_same_fmt_for_name(const AP_Logger::log_write_fmt *f,
  704. const char *name,
  705. const char *labels,
  706. const char *units,
  707. const char *mults,
  708. const char *fmt) const
  709. {
  710. bool passed = true;
  711. if (!streq(f->name, name)) {
  712. // why exactly were we called?!
  713. Debug("format names differ (%s) != (%s)", f->name, name);
  714. passed = false;
  715. }
  716. if (!streq(f->labels, labels)) {
  717. Debug("format labels differ (%s) vs (%s)", f->labels, labels);
  718. passed = false;
  719. }
  720. if ((f->units != nullptr && units == nullptr) ||
  721. (f->units == nullptr && units != nullptr) ||
  722. (units !=nullptr && !streq(f->units, units))) {
  723. Debug("format units differ (%s) vs (%s)",
  724. (f->units ? f->units : "nullptr"),
  725. (units ? units : "nullptr"));
  726. passed = false;
  727. }
  728. if ((f->mults != nullptr && mults == nullptr) ||
  729. (f->mults == nullptr && mults != nullptr) ||
  730. (mults != nullptr && !streq(f->mults, mults))) {
  731. Debug("format mults differ (%s) vs (%s)",
  732. (f->mults ? f->mults : "nullptr"),
  733. (mults ? mults : "nullptr"));
  734. passed = false;
  735. }
  736. if (!streq(f->fmt, fmt)) {
  737. Debug("format fmt differ (%s) vs (%s)",
  738. (f->fmt ? f->fmt : "nullptr"),
  739. (fmt ? fmt : "nullptr"));
  740. passed = false;
  741. }
  742. if (!passed) {
  743. Debug("Format definition must be consistent for every call of Write");
  744. abort();
  745. }
  746. }
  747. #endif
  748. AP_Logger::log_write_fmt *AP_Logger::msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
  749. {
  750. struct log_write_fmt *f;
  751. for (f = log_write_fmts; f; f=f->next) {
  752. if (f->name == name) { // ptr comparison
  753. // already have an ID for this name:
  754. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  755. assert_same_fmt_for_name(f, name, labels, units, mults, fmt);
  756. #endif
  757. return f;
  758. }
  759. }
  760. f = (struct log_write_fmt *)calloc(1, sizeof(*f));
  761. if (f == nullptr) {
  762. // out of memory
  763. return nullptr;
  764. }
  765. // no message type allocated for this name. Try to allocate one:
  766. int16_t msg_type = find_free_msg_type();
  767. if (msg_type == -1) {
  768. free(f);
  769. return nullptr;
  770. }
  771. f->msg_type = msg_type;
  772. f->name = name;
  773. f->fmt = fmt;
  774. f->labels = labels;
  775. f->units = units;
  776. f->mults = mults;
  777. int16_t tmp = Write_calc_msg_len(fmt);
  778. if (tmp == -1) {
  779. free(f);
  780. return nullptr;
  781. }
  782. f->msg_len = tmp;
  783. // add to front of list
  784. f->next = log_write_fmts;
  785. log_write_fmts = f;
  786. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  787. char ls_name[LS_NAME_SIZE] = {};
  788. char ls_format[LS_FORMAT_SIZE] = {};
  789. char ls_labels[LS_LABELS_SIZE] = {};
  790. char ls_units[LS_UNITS_SIZE] = {};
  791. char ls_multipliers[LS_MULTIPLIERS_SIZE] = {};
  792. struct LogStructure ls = {
  793. f->msg_type,
  794. f->msg_len,
  795. ls_name,
  796. ls_format,
  797. ls_labels,
  798. ls_units,
  799. ls_multipliers
  800. };
  801. memcpy((char*)ls_name, f->name, MIN(sizeof(ls_name), strlen(f->name)));
  802. memcpy((char*)ls_format, f->fmt, MIN(sizeof(ls_format), strlen(f->fmt)));
  803. memcpy((char*)ls_labels, f->labels, MIN(sizeof(ls_labels), strlen(f->labels)));
  804. if (f->units != nullptr) {
  805. memcpy((char*)ls_units, f->units, MIN(sizeof(ls_units), strlen(f->units)));
  806. } else {
  807. memset((char*)ls_units, '?', MIN(sizeof(ls_format), strlen(f->fmt)));
  808. }
  809. if (f->mults != nullptr) {
  810. memcpy((char*)ls_multipliers, f->mults, MIN(sizeof(ls_multipliers), strlen(f->mults)));
  811. } else {
  812. memset((char*)ls_multipliers, '?', MIN(sizeof(ls_format), strlen(f->fmt)));
  813. }
  814. if (!validate_structure(&ls, (int16_t)-1)) {
  815. Debug("Log structure invalid");
  816. abort();
  817. }
  818. #endif
  819. return f;
  820. }
  821. const struct LogStructure *AP_Logger::structure_for_msg_type(const uint8_t msg_type)
  822. {
  823. for (uint16_t i=0; i<_num_types;i++) {
  824. const struct LogStructure *s = structure(i);
  825. if (s->msg_type == msg_type) {
  826. // in use
  827. return s;
  828. }
  829. }
  830. return nullptr;
  831. }
  832. const struct AP_Logger::log_write_fmt *AP_Logger::log_write_fmt_for_msg_type(const uint8_t msg_type) const
  833. {
  834. struct log_write_fmt *f;
  835. for (f = log_write_fmts; f; f=f->next) {
  836. if (f->msg_type == msg_type) {
  837. return f;
  838. }
  839. }
  840. return nullptr;
  841. }
  842. // returns true if the msg_type is already taken
  843. bool AP_Logger::msg_type_in_use(const uint8_t msg_type) const
  844. {
  845. // check static list of messages (e.g. from LOG_BASE_STRUCTURES)
  846. // check the write format types to see if we've used this one
  847. for (uint16_t i=0; i<_num_types;i++) {
  848. if (structure(i)->msg_type == msg_type) {
  849. // in use
  850. return true;
  851. }
  852. }
  853. struct log_write_fmt *f;
  854. for (f = log_write_fmts; f; f=f->next) {
  855. if (f->msg_type == msg_type) {
  856. return true;
  857. }
  858. }
  859. return false;
  860. }
  861. // find a free message type
  862. int16_t AP_Logger::find_free_msg_type() const
  863. {
  864. // avoid using 255 here; perhaps we want to use it to extend things later
  865. for (uint16_t msg_type=254; msg_type>0; msg_type--) { // more likely to be free at end
  866. if (! msg_type_in_use(msg_type)) {
  867. return msg_type;
  868. }
  869. }
  870. return -1;
  871. }
  872. /*
  873. * It is assumed that logstruct's char* variables are valid strings of
  874. * maximum lengths for those fields (given in LogStructure.h e.g. LS_NAME_SIZE)
  875. */
  876. bool AP_Logger::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
  877. {
  878. // find log structure information corresponding to msg_type:
  879. struct log_write_fmt *f;
  880. for (f = log_write_fmts; f; f=f->next) {
  881. if(f->msg_type == msg_type) {
  882. break;
  883. }
  884. }
  885. if (!f) {
  886. return false;
  887. }
  888. logstruct.msg_type = msg_type;
  889. strncpy((char*)logstruct.name, f->name, LS_NAME_SIZE);
  890. strncpy((char*)logstruct.format, f->fmt, LS_FORMAT_SIZE);
  891. strncpy((char*)logstruct.labels, f->labels, LS_LABELS_SIZE);
  892. if (f->units != nullptr) {
  893. strncpy((char*)logstruct.units, f->units, LS_UNITS_SIZE);
  894. } else {
  895. memset((char*)logstruct.units, '\0', LS_UNITS_SIZE);
  896. memset((char*)logstruct.units, '?', MIN(LS_UNITS_SIZE,strlen(logstruct.format)));
  897. }
  898. if (f->mults != nullptr) {
  899. strncpy((char*)logstruct.multipliers, f->mults, LS_MULTIPLIERS_SIZE);
  900. } else {
  901. memset((char*)logstruct.multipliers, '\0', LS_MULTIPLIERS_SIZE);
  902. memset((char*)logstruct.multipliers, '?', MIN(LS_MULTIPLIERS_SIZE, strlen(logstruct.format)));
  903. // special magic to set units/mults for TimeUS, by far and
  904. // away the most common first field
  905. if (!strncmp(logstruct.labels, "TimeUS,", MIN(LS_LABELS_SIZE, strlen("TimeUS,")))) {
  906. ((char*)(logstruct.units))[0] = 's';
  907. ((char*)(logstruct.multipliers))[0] = 'F';
  908. }
  909. }
  910. logstruct.msg_len = f->msg_len;
  911. return true;
  912. }
  913. /* calculate the length of output of a format string. Note that this
  914. * returns an int16_t; if it returns -1 then an error has occurred.
  915. * This was mechanically converted from init_field_types in
  916. * Tools/Replay/MsgHandler.cpp */
  917. int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const
  918. {
  919. uint8_t len = LOG_PACKET_HEADER_LEN;
  920. for (uint8_t i=0; i<strlen(fmt); i++) {
  921. switch(fmt[i]) {
  922. case 'a' : len += sizeof(int16_t[32]); break;
  923. case 'b' : len += sizeof(int8_t); break;
  924. case 'c' : len += sizeof(int16_t); break;
  925. case 'd' : len += sizeof(double); break;
  926. case 'e' : len += sizeof(int32_t); break;
  927. case 'f' : len += sizeof(float); break;
  928. case 'h' : len += sizeof(int16_t); break;
  929. case 'i' : len += sizeof(int32_t); break;
  930. case 'n' : len += sizeof(char[4]); break;
  931. case 'B' : len += sizeof(uint8_t); break;
  932. case 'C' : len += sizeof(uint16_t); break;
  933. case 'E' : len += sizeof(uint32_t); break;
  934. case 'H' : len += sizeof(uint16_t); break;
  935. case 'I' : len += sizeof(uint32_t); break;
  936. case 'L' : len += sizeof(int32_t); break;
  937. case 'M' : len += sizeof(uint8_t); break;
  938. case 'N' : len += sizeof(char[16]); break;
  939. case 'Z' : len += sizeof(char[64]); break;
  940. case 'q' : len += sizeof(int64_t); break;
  941. case 'Q' : len += sizeof(uint64_t); break;
  942. default:
  943. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  944. AP_HAL::panic("Unknown format specifier (%c)", fmt[i]);
  945. #endif
  946. return -1;
  947. }
  948. }
  949. return len;
  950. }
  951. /* End of Write support */
  952. #undef FOR_EACH_BACKEND
  953. // Write information about a series of IMU readings to log:
  954. bool AP_Logger::Write_ISBH(const uint16_t seqno,
  955. const AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
  956. const uint8_t sensor_instance,
  957. const uint16_t mult,
  958. const uint16_t sample_count,
  959. const uint64_t sample_us,
  960. const float sample_rate_hz)
  961. {
  962. if (_next_backend == 0) {
  963. return false;
  964. }
  965. const struct log_ISBH pkt{
  966. LOG_PACKET_HEADER_INIT(LOG_ISBH_MSG),
  967. time_us : AP_HAL::micros64(),
  968. seqno : seqno,
  969. sensor_type : (uint8_t)sensor_type,
  970. instance : sensor_instance,
  971. multiplier : mult,
  972. sample_count : sample_count,
  973. sample_us : sample_us,
  974. sample_rate_hz : sample_rate_hz,
  975. };
  976. // only the first backend need succeed for us to be successful
  977. for (uint8_t i=1; i<_next_backend; i++) {
  978. backends[i]->WriteBlock(&pkt, sizeof(pkt));
  979. }
  980. return backends[0]->WriteBlock(&pkt, sizeof(pkt));
  981. }
  982. // Write a series of IMU readings to log:
  983. bool AP_Logger::Write_ISBD(const uint16_t isb_seqno,
  984. const uint16_t seqno,
  985. const int16_t x[32],
  986. const int16_t y[32],
  987. const int16_t z[32])
  988. {
  989. if (_next_backend == 0) {
  990. return false;
  991. }
  992. struct log_ISBD pkt = {
  993. LOG_PACKET_HEADER_INIT(LOG_ISBD_MSG),
  994. time_us : AP_HAL::micros64(),
  995. isb_seqno : isb_seqno,
  996. seqno : seqno
  997. };
  998. memcpy(pkt.x, x, sizeof(pkt.x));
  999. memcpy(pkt.y, y, sizeof(pkt.y));
  1000. memcpy(pkt.z, z, sizeof(pkt.z));
  1001. // only the first backend need succeed for us to be successful
  1002. for (uint8_t i=1; i<_next_backend; i++) {
  1003. backends[i]->WriteBlock(&pkt, sizeof(pkt));
  1004. }
  1005. return backends[0]->WriteBlock(&pkt, sizeof(pkt));
  1006. }
  1007. // Wrote an event packet
  1008. void AP_Logger::Write_Event(Log_Event id)
  1009. {
  1010. const struct log_Event pkt{
  1011. LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
  1012. time_us : AP_HAL::micros64(),
  1013. id : id
  1014. };
  1015. WriteCriticalBlock(&pkt, sizeof(pkt));
  1016. }
  1017. // Write an error packet
  1018. void AP_Logger::Write_Error(LogErrorSubsystem sub_system,
  1019. LogErrorCode error_code)
  1020. {
  1021. const struct log_Error pkt{
  1022. LOG_PACKET_HEADER_INIT(LOG_ERROR_MSG),
  1023. time_us : AP_HAL::micros64(),
  1024. sub_system : uint8_t(sub_system),
  1025. error_code : uint8_t(error_code),
  1026. };
  1027. WriteCriticalBlock(&pkt, sizeof(pkt));
  1028. }
  1029. /*
  1030. return true if we should log while disarmed
  1031. */
  1032. bool AP_Logger::log_while_disarmed(void) const
  1033. {
  1034. if (_force_log_disarmed) {
  1035. return true;
  1036. }
  1037. if (_params.log_disarmed != 0) {
  1038. return true;
  1039. }
  1040. uint32_t now = AP_HAL::millis();
  1041. uint32_t persist_ms = HAL_LOGGER_ARM_PERSIST*1000U;
  1042. // keep logging for HAL_LOGGER_ARM_PERSIST seconds after disarming
  1043. const uint32_t arm_change_ms = hal.util->get_last_armed_change();
  1044. if (!hal.util->get_soft_armed() && arm_change_ms != 0 && now - arm_change_ms < persist_ms) {
  1045. return true;
  1046. }
  1047. // keep logging for HAL_LOGGER_ARM_PERSIST seconds after an arming failure
  1048. if (_last_arming_failure_ms && now - _last_arming_failure_ms < persist_ms) {
  1049. return true;
  1050. }
  1051. return false;
  1052. }
  1053. namespace AP {
  1054. AP_Logger &logger()
  1055. {
  1056. return *AP_Logger::get_singleton();
  1057. }
  1058. };