APM:Libraries
DataFlash.cpp
Go to the documentation of this file.
1 #include "DataFlash.h"
2 
3 #include "DataFlash_Backend.h"
4 
5 #include "DataFlash_File.h"
6 #include "DataFlash_File_sd.h"
7 #include "DataFlash_MAVLink.h"
8 #include <GCS_MAVLink/GCS.h>
9 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
10 #include "DataFlash_Revo.h"
11 #endif
12 
13 
15 
16 extern const AP_HAL::HAL& hal;
17 
19  // @Param: _BACKEND_TYPE
20  // @DisplayName: DataFlash Backend Storage type
21  // @Description: 0 for None, 1 for File, 2 for dataflash mavlink, 3 for both file and dataflash
22  // @Values: 0:None,1:File,2:MAVLink,3:BothFileAndMAVLink
23  // @User: Standard
25 
26  // @Param: _FILE_BUFSIZE
27  // @DisplayName: Maximum DataFlash File Backend buffer size (in kilobytes)
28  // @Description: The DataFlash_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.
29  // @User: Standard
30  AP_GROUPINFO("_FILE_BUFSIZE", 1, DataFlash_Class, _params.file_bufsize, 16),
31 
32  // @Param: _DISARMED
33  // @DisplayName: Enable logging while disarmed
34  // @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
35  // @Values: 0:Disabled,1:Enabled
36  // @User: Standard
37  AP_GROUPINFO("_DISARMED", 2, DataFlash_Class, _params.log_disarmed, 0),
38 
39  // @Param: _REPLAY
40  // @DisplayName: Enable logging of information needed for Replay
41  // @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
42  // @Values: 0:Disabled,1:Enabled
43  // @User: Standard
44  AP_GROUPINFO("_REPLAY", 3, DataFlash_Class, _params.log_replay, 0),
45 
46  // @Param: _FILE_DSRMROT
47  // @DisplayName: Stop logging to current file on disarm
48  // @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.
49  // @Values: 0:Disabled,1:Enabled
50  // @User: Standard
51  AP_GROUPINFO("_FILE_DSRMROT", 4, DataFlash_Class, _params.file_disarm_rot, 0),
52 
53  // @Param: _MAV_BUFSIZE
54  // @DisplayName: Maximum DataFlash MAVLink Backend buffer size
55  // @Description: Maximum amount of memory to allocate to DataFlash-over-mavlink
56  // @User: Advanced
57  // @Units: kB
58  AP_GROUPINFO("_MAV_BUFSIZE", 5, DataFlash_Class, _params.mav_bufsize, 8),
59 
61 };
62 
63 #define streq(x, y) (!strcmp(x, y))
64 
65 DataFlash_Class::DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask)
66  : _firmware_string(firmware_string)
67  , _log_bitmask(log_bitmask)
68 {
70  if (_instance != nullptr) {
71  AP_HAL::panic("DataFlash must be singleton");
72  }
73 
74  _instance = this;
75 }
76 
77 void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_types)
78 {
79  gcs().send_text(MAV_SEVERITY_INFO, "Preparing log system");
80 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
81  validate_structures(structures, num_types);
82  dump_structures(structures, num_types);
83 #endif
85  AP_HAL::panic("Too many backends");
86  return;
87  }
88  _num_types = num_types;
89  _structures = structures;
90 
91 #if defined(HAL_BOARD_LOG_DIRECTORY)
92  #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO
93  if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
94  _params.backend_types == DATAFLASH_BACKEND_BOTH) {
95  DFMessageWriter_DFLogStart *message_writer =
97  if (message_writer != nullptr) {
98  backends[_next_backend] = new DataFlash_File(*this,
99  message_writer,
101  }
102  if (backends[_next_backend] == nullptr) {
103  hal.console->printf("Unable to open DataFlash_File");
104  } else {
105  _next_backend++;
106  }
107  }
108  #elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
109 
110  if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
111  _params.backend_types == DATAFLASH_BACKEND_BOTH) {
112 
113  DFMessageWriter_DFLogStart *message_writer =
115  if (message_writer != nullptr) {
116 
117  #if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)
118  backends[_next_backend] = new DataFlash_File(*this, message_writer, HAL_BOARD_LOG_DIRECTORY);
119  #else
120  backends[_next_backend] = new DataFlash_Revo(*this, message_writer); // restore dataflash logs
121  #endif
122  }
123 
124  if (backends[_next_backend] == nullptr) {
125  printf("Unable to open DataFlash_Revo");
126  } else {
127  _next_backend++;
128  }
129  }
130  #endif
131 #endif // HAL_BOARD_LOG_DIRECTORY
132 
133 #if DATAFLASH_MAVLINK_SUPPORT
134  if (_params.backend_types == DATAFLASH_BACKEND_MAVLINK ||
135  _params.backend_types == DATAFLASH_BACKEND_BOTH) {
137  AP_HAL::panic("Too many backends");
138  return;
139  }
140  DFMessageWriter_DFLogStart *message_writer =
142  if (message_writer != nullptr) {
144  message_writer);
145  }
146  if (backends[_next_backend] == nullptr) {
147  hal.console->printf("Unable to open DataFlash_MAVLink");
148  } else {
149  _next_backend++;
150  }
151  }
152 #endif
153 
154  for (uint8_t i=0; i<_next_backend; i++) {
155  backends[i]->Init();
156  }
157 
158  Prep();
159 
160  EnableWrites(true);
161 
162  gcs().send_text(MAV_SEVERITY_INFO, "Prepared log system");
163 }
164 
165 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
166 #include <stdio.h>
167 
168 #define DEBUG_LOG_STRUCTURES 0
169 
170 extern const AP_HAL::HAL& hal;
171 #define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
172 
174 static uint8_t count_commas(const char *string)
175 {
176  uint8_t ret = 0;
177  for (uint8_t i=0; i<strlen(string); i++) {
178  if (string[i] == ',') {
179  ret++;
180  }
181  }
182  return ret;
183 }
184 
186 const char* DataFlash_Class::unit_name(const uint8_t unit_id)
187 {
188  for(uint8_t i=0; i<unit_id; i++) {
189  if (_units[i].ID == unit_id) {
190  return _units[i].unit;
191  }
192  }
193  return NULL;
194 }
195 
197 double DataFlash_Class::multiplier_name(const uint8_t multiplier_id)
198 {
199  for(uint8_t i=0; i<multiplier_id; i++) {
200  if (_multipliers[i].ID == multiplier_id) {
201  return _multipliers[i].multiplier;
202  }
203  }
204  // Should we abort here?
205  return 1.0f;
206 }
207 
209 void DataFlash_Class::dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
210 {
211  ::fprintf(stderr, " %s (%s)*(%f)\n", label, unit_name(logstructure->units[fieldnum]), multiplier_name(logstructure->multipliers[fieldnum]));
212 }
213 
216 void DataFlash_Class::dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
217 {
218 #if DEBUG_LOG_STRUCTURES
219  for (uint16_t i=0; i<num_types; i++) {
220  const struct LogStructure *logstructure = &logstructures[i];
221  ::fprintf(stderr, "%s\n", logstructure->name);
222  char label[32] = { };
223  uint8_t labeloffset = 0;
224  int8_t fieldnum = 0;
225  for (uint8_t j=0; j<strlen(logstructure->labels); j++) {
226  char labelchar = logstructure->labels[j];
227  if (labelchar == '\0') {
228  break;
229  }
230  if (labelchar == ',') {
231  dump_structure_field(logstructure, label, fieldnum);
232  fieldnum++;
233  labeloffset = 0;
234  memset(label, '\0', 32);
235  } else {
236  label[labeloffset++] = labelchar;
237  }
238  }
239  dump_structure_field(logstructure, label, fieldnum);
240  ::fprintf(stderr, "\n"); // just add a CR to the output
241  }
242 #endif
243 }
244 
245 bool DataFlash_Class::validate_structure(const struct LogStructure *logstructure, const int16_t offset)
246 {
247  bool passed = true;
248 
249 #if DEBUG_LOG_STRUCTURES
250  Debug("offset=%d ID=%d NAME=%s\n", offset, logstructure->msg_type, logstructure->name);
251 #endif
252 
253  // fields must be null-terminated
254 #define CHECK_ENTRY(fieldname,fieldname_s,fieldlen) \
255  do { \
256  if (strnlen(logstructure->fieldname, fieldlen) > fieldlen-1) { \
257  Debug("Message " fieldname_s " not NULL-terminated or too long"); \
258  passed = false; \
259  } \
260  } while (false)
261  CHECK_ENTRY(name, "name", LS_NAME_SIZE);
262  CHECK_ENTRY(format, "format", LS_FORMAT_SIZE);
263  CHECK_ENTRY(labels, "labels", LS_LABELS_SIZE);
264  CHECK_ENTRY(units, "units", LS_UNITS_SIZE);
266 #undef CHECK_ENTRY
267 
268  // ensure each message ID is only used once
269  if (seen_ids[logstructure->msg_type]) {
270  Debug("ID %d used twice (LogStructure offset=%d)", logstructure->msg_type, offset);
271  passed = false;
272  }
273  seen_ids[logstructure->msg_type] = true;
274 
275  // ensure we have enough labels to cover columns
276  uint8_t fieldcount = strlen(logstructure->format);
277  uint8_t labelcount = count_commas(logstructure->labels)+1;
278  if (fieldcount != labelcount) {
279  Debug("fieldcount=%u does not match labelcount=%u",
280  fieldcount, labelcount);
281  passed = false;
282  }
283 
284  // check that the structure is of an appropriate length to take fields
285  const int16_t msg_len = Log_Write_calc_msg_len(logstructure->format);
286  if (msg_len != logstructure->msg_len) {
287  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);
288  passed = false;
289  }
290 
291  // ensure we have units for each field:
292  if (strlen(logstructure->units) != fieldcount) {
293  Debug("fieldcount=%u does not match unitcount=%lu",
294  fieldcount, strlen(logstructure->units));
295  passed = false;
296  }
297 
298  // ensure we have multipliers for each field
299  if (strlen(logstructure->multipliers) != fieldcount) {
300  Debug("fieldcount=%u does not match multipliercount=%lu",
301  fieldcount, strlen(logstructure->multipliers));
302  passed = false;
303  }
304 
305  // ensure the FMTU messages reference valid units
306  for (uint8_t j=0; j<strlen(logstructure->units); j++) {
307  char logunit = logstructure->units[j];
308  uint8_t k;
309  for (k=0; k<_num_units; k++) {
310  if (logunit == _units[k].ID) {
311  // found this one
312  break;
313  }
314  }
315  if (k == _num_units) {
316  Debug("invalid unit=%c", logunit);
317  passed = false;
318  }
319  }
320 
321  // ensure the FMTU messages reference valid multipliers
322  for (uint8_t j=0; j<strlen(logstructure->multipliers); j++) {
323  char logmultiplier = logstructure->multipliers[j];
324  uint8_t k;
325  for (k=0; k<_num_multipliers; k++) {
326  if (logmultiplier == _multipliers[k].ID) {
327  // found this one
328  break;
329  }
330  }
331  if (k == _num_multipliers) {
332  Debug("invalid multiplier=%c", logmultiplier);
333  passed = false;
334  }
335  }
336  return passed;
337 }
338 
339 void DataFlash_Class::validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
340 {
341  Debug("Validating structures");
342  bool passed = true;
343 
344  for (uint16_t i=0; i<num_types; i++) {
345  const struct LogStructure *logstructure = &logstructures[i];
346  passed = validate_structure(logstructure, i) && passed;
347  }
348  if (!passed) {
349  Debug("Log structures are invalid");
350  abort();
351  }
352 }
353 
354 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
355 
356 const struct LogStructure *DataFlash_Class::structure(uint16_t num) const
357 {
358  return &_structures[num];
359 }
360 
362 {
363  return _next_backend != 0;
364 }
366 {
367  if (_next_backend == 0) {
368  return false;
369  }
370  for (uint8_t i=0; i<_next_backend; i++) {
371  if (backends[i]->logging_enabled()) {
372  return true;
373  }
374  }
375  return false;
376 }
378 {
379  if (_next_backend < 1) {
380  // we should not have been called!
381  return true;
382  }
383  for (uint8_t i=0; i<_next_backend; i++) {
384  if (backends[i]->logging_failed()) {
385  return true;
386  }
387  }
388  return false;
389 }
390 
392 {
393  char msg[64] {};
394 
395  va_list ap;
396  va_start(ap, fmt);
397  hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
398  va_end(ap);
399 
400  Log_Write_Message(msg);
401 }
402 
404 {
405  for (uint8_t i=0; i<_next_backend; i++) {
406  if (backends[i] == backend) { // pointer comparison!
407  // reset sent masks
408  for (struct log_write_fmt *f = log_write_fmts; f; f=f->next) {
409  f->sent_mask &= ~(1<<i);
410  }
411  break;
412  }
413  }
414 }
415 
416 bool DataFlash_Class::should_log(const uint32_t mask) const
417 {
418  if (!(mask & _log_bitmask)) {
419  return false;
420  }
421  if (!vehicle_is_armed() && !log_while_disarmed()) {
422  return false;
423  }
424  if (in_log_download()) {
425  return false;
426  }
427  if (_next_backend == 0) {
428  return false;
429  }
430  return true;
431 }
432 
433 const struct UnitStructure *DataFlash_Class::unit(uint16_t num) const
434 {
435  return &_units[num];
436 }
437 
439 {
440  return &log_Multipliers[num];
441 }
442 
443 #define FOR_EACH_BACKEND(methodcall) \
444  do { \
445  for (uint8_t i=0; i<_next_backend; i++) { \
446  backends[i]->methodcall; \
447  } \
448  } while (0)
449 
451 {
453 }
454 
455 void DataFlash_Class::setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
456 {
457  _vehicle_messages = writer;
458 }
459 
460 void DataFlash_Class::set_vehicle_armed(const bool armed_state)
461 {
462  if (armed_state == _armed) {
463  // no change in status
464  return;
465  }
466  _armed = armed_state;
467 
468  if (!_armed) {
469  // went from armed to disarmed
470  FOR_EACH_BACKEND(vehicle_was_disarmed());
471  }
472 
473 }
474 
475 
477  FOR_EACH_BACKEND(set_mission(mission));
478 }
479 
480 // start functions pass straight through to backend:
481 void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size) {
482  FOR_EACH_BACKEND(WriteBlock(pBuffer, size));
483 }
484 
485 void DataFlash_Class::WriteCriticalBlock(const void *pBuffer, uint16_t size) {
486  FOR_EACH_BACKEND(WriteCriticalBlock(pBuffer, size));
487 }
488 
489 void DataFlash_Class::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) {
490  FOR_EACH_BACKEND(WritePrioritisedBlock(pBuffer, size, is_critical));
491 }
492 
493 // change me to "DoTimeConsumingPreparations"?
496 }
497 // change me to "LoggingAvailable"?
499  for (uint8_t i=0; i< _next_backend; i++) {
500  if (backends[i]->CardInserted()) {
501  return true;
502  }
503  }
504  return false;
505 }
506 
509 }
510 
512 {
513  FOR_EACH_BACKEND(stop_logging());
514 }
515 
517  if (_next_backend == 0) {
518  return 0;
519  }
520  return backends[0]->find_last_log();
521 }
522 void DataFlash_Class::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) {
523  if (_next_backend == 0) {
524  return;
525  }
526  backends[0]->get_log_boundaries(log_num, start_page, end_page);
527 }
528 void DataFlash_Class::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) {
529  if (_next_backend == 0) {
530  return;
531  }
532  backends[0]->get_log_info(log_num, size, time_utc);
533 }
534 int16_t DataFlash_Class::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) {
535  if (_next_backend == 0) {
536  return 0;
537  }
538  return backends[0]->get_log_data(log_num, page, offset, len, data);
539 }
541  if (_next_backend == 0) {
542  return 0;
543  }
544  return backends[0]->get_num_logs();
545 }
546 
547 /* we're started if any of the backends are started */
549  for (uint8_t i=0; i< _next_backend; i++) {
550  if (backends[i]->logging_started()) {
551  return true;
552  }
553  }
554  return false;
555 }
556 
557 void DataFlash_Class::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* msg)
558 {
559  switch (msg->msgid) {
560  case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
561  FOR_EACH_BACKEND(remote_log_block_status_msg(link.get_chan(), msg));
562  break;
563  case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
564  FALLTHROUGH;
565  case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
566  FALLTHROUGH;
567  case MAVLINK_MSG_ID_LOG_ERASE:
568  FALLTHROUGH;
569  case MAVLINK_MSG_ID_LOG_REQUEST_END:
570  handle_log_message(link, msg);
571  break;
572  }
573 }
574 
576  handle_log_send();
578 }
579 
580 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
581  // currently only DataFlash_File support this:
584 }
585 #endif
586 
587 
589 {
591 }
592 
593 void DataFlash_Class::Log_Write_Message(const char *message)
594 {
596 }
597 
598 void DataFlash_Class::Log_Write_Mode(uint8_t mode, uint8_t reason)
599 {
600  FOR_EACH_BACKEND(Log_Write_Mode(mode, reason));
601 }
602 
604 {
606 }
607 
609  const AP_Mission::Mission_Command &cmd)
610 {
612 }
613 
615 {
616  if (_next_backend == 0) {
617  return 0;
618  }
619  return backends[0]->num_dropped();
620 }
621 
622 
623 // end functions pass straight through to backend
624 
626 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
627  AP_HAL::panic("Internal DataFlash error");
628 #endif
629 }
630 
631 /* Log_Write support */
632 void DataFlash_Class::Log_Write(const char *name, const char *labels, const char *fmt, ...)
633 {
634  va_list arg_list;
635 
636  va_start(arg_list, fmt);
637  Log_WriteV(name, labels, nullptr, nullptr, fmt, arg_list);
638  va_end(arg_list);
639 }
640 
641 void DataFlash_Class::Log_Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
642 {
643  va_list arg_list;
644 
645  va_start(arg_list, fmt);
646  Log_WriteV(name, labels, units, mults, fmt, arg_list);
647  va_end(arg_list);
648 }
649 
650 void DataFlash_Class::Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list)
651 {
652  struct log_write_fmt *f = msg_fmt_for_name(name, labels, units, mults, fmt);
653  if (f == nullptr) {
654  // unable to map name to a messagetype; could be out of
655  // msgtypes, could be out of slots, ...
656  internal_error();
657  return;
658  }
659 
660  for (uint8_t i=0; i<_next_backend; i++) {
661  if (!(f->sent_mask & (1U<<i))) {
662  if (!backends[i]->Log_Write_Emit_FMT(f->msg_type)) {
663  continue;
664  }
665  f->sent_mask |= (1U<<i);
666  }
667  va_list arg_copy;
668  va_copy(arg_copy, arg_list);
669  backends[i]->Log_Write(f->msg_type, arg_copy);
670  va_end(arg_copy);
671  }
672 }
673 
674 
675 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
677  const char *name,
678  const char *labels,
679  const char *units,
680  const char *mults,
681  const char *fmt) const
682 {
683  bool passed = true;
684  if (!streq(f->name, name)) {
685  // why exactly were we called?!
686  Debug("format names differ (%s) != (%s)", f->name, name);
687  passed = false;
688  }
689  if (!streq(f->labels, labels)) {
690  Debug("format labels differ (%s) vs (%s)", f->labels, labels);
691  passed = false;
692  }
693  if ((f->units != nullptr && units == nullptr) ||
694  (f->units == nullptr && units != nullptr) ||
695  (units !=nullptr && !streq(f->units, units))) {
696  Debug("format units differ (%s) vs (%s)",
697  (f->units ? f->units : "nullptr"),
698  (units ? units : "nullptr"));
699  passed = false;
700  }
701  if ((f->mults != nullptr && mults == nullptr) ||
702  (f->mults == nullptr && mults != nullptr) ||
703  (mults != nullptr && !streq(f->mults, mults))) {
704  Debug("format mults differ (%s) vs (%s)",
705  (f->mults ? f->mults : "nullptr"),
706  (mults ? mults : "nullptr"));
707  passed = false;
708  }
709  if (!streq(f->fmt, fmt)) {
710  Debug("format fmt differ (%s) vs (%s)",
711  (f->fmt ? f->fmt : "nullptr"),
712  (fmt ? fmt : "nullptr"));
713  passed = false;
714  }
715  if (!passed) {
716  Debug("Format definition must be consistent for every call of Log_Write");
717  abort();
718  }
719 }
720 #endif
721 
722 DataFlash_Class::log_write_fmt *DataFlash_Class::msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
723 {
724  struct log_write_fmt *f;
725  for (f = log_write_fmts; f; f=f->next) {
726  if (f->name == name) { // ptr comparison
727  // already have an ID for this name:
728 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
729  assert_same_fmt_for_name(f, name, labels, units, mults, fmt);
730 #endif
731  return f;
732  }
733  }
734  f = (struct log_write_fmt *)calloc(1, sizeof(*f));
735  if (f == nullptr) {
736  // out of memory
737  return nullptr;
738  }
739  // no message type allocated for this name. Try to allocate one:
740  int16_t msg_type = find_free_msg_type();
741  if (msg_type == -1) {
742  free(f);
743  return nullptr;
744  }
745  f->msg_type = msg_type;
746  f->name = name;
747  f->fmt = fmt;
748  f->labels = labels;
749  f->units = units;
750  f->mults = mults;
751 
752  int16_t tmp = Log_Write_calc_msg_len(fmt);
753  if (tmp == -1) {
754  free(f);
755  return nullptr;
756  }
757 
758  f->msg_len = tmp;
759 
760  // add to front of list
761  f->next = log_write_fmts;
762  log_write_fmts = f;
763 
764 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
765  char ls_name[LS_NAME_SIZE] = {};
766  char ls_format[LS_FORMAT_SIZE] = {};
767  char ls_labels[LS_LABELS_SIZE] = {};
768  char ls_units[LS_UNITS_SIZE] = {};
769  char ls_multipliers[LS_MULTIPLIERS_SIZE] = {};
770  struct LogStructure ls = {
771  f->msg_type,
772  f->msg_len,
773  ls_name,
774  ls_format,
775  ls_labels,
776  ls_units,
777  ls_multipliers
778  };
779  memcpy((char*)ls_name, f->name, MIN(sizeof(ls_name), strlen(f->name)));
780  memcpy((char*)ls_format, f->fmt, MIN(sizeof(ls_format), strlen(f->fmt)));
781  memcpy((char*)ls_labels, f->labels, MIN(sizeof(ls_labels), strlen(f->labels)));
782  if (f->units != nullptr) {
783  memcpy((char*)ls_units, f->units, MIN(sizeof(ls_units), strlen(f->units)));
784  } else {
785  memset((char*)ls_units, '?', MIN(sizeof(ls_format), strlen(f->fmt)));
786  }
787  if (f->mults != nullptr) {
788  memcpy((char*)ls_multipliers, f->mults, MIN(sizeof(ls_multipliers), strlen(f->mults)));
789  } else {
790  memset((char*)ls_multipliers, '?', MIN(sizeof(ls_format), strlen(f->fmt)));
791  }
792  validate_structure(&ls, (int16_t)-1);
793 #endif
794 
795  return f;
796 }
797 
798 // returns true if the msg_type is already taken
800 {
801  // check static list of messages (e.g. from LOG_BASE_STRUCTURES)
802  // check the write format types to see if we've used this one
803  for (uint16_t i=0; i<_num_types;i++) {
804  if (structure(i)->msg_type == msg_type) {
805  // in use
806  return true;
807  }
808  }
809 
810  struct log_write_fmt *f;
811  for (f = log_write_fmts; f; f=f->next) {
812  if (f->msg_type == msg_type) {
813  return true;
814  }
815  }
816  return false;
817 }
818 
819 // find a free message type
821 {
822  // avoid using 255 here; perhaps we want to use it to extend things later
823  for (uint16_t msg_type=254; msg_type>0; msg_type--) { // more likely to be free at end
824  if (! msg_type_in_use(msg_type)) {
825  return msg_type;
826  }
827  }
828  return -1;
829 }
830 
831 /*
832  * It is assumed that logstruct's char* variables are valid strings of
833  * maximum lengths for those fields (given in LogStructure.h e.g. LS_NAME_SIZE)
834  */
835 bool DataFlash_Class::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
836 {
837  // find log structure information corresponding to msg_type:
838  struct log_write_fmt *f;
839  for (f = log_write_fmts; f; f=f->next) {
840  if(f->msg_type == msg_type) {
841  break;
842  }
843  }
844 
845  if (!f) {
846  return false;
847  }
848 
849  logstruct.msg_type = msg_type;
850  strncpy((char*)logstruct.name, f->name, LS_NAME_SIZE);
851  strncpy((char*)logstruct.format, f->fmt, LS_FORMAT_SIZE);
852  strncpy((char*)logstruct.labels, f->labels, LS_LABELS_SIZE);
853  if (f->units != nullptr) {
854  strncpy((char*)logstruct.units, f->units, LS_UNITS_SIZE);
855  } else {
856  memset((char*)logstruct.units, '\0', LS_UNITS_SIZE);
857  memset((char*)logstruct.units, '?', MIN(LS_UNITS_SIZE,strlen(logstruct.format)));
858  }
859  if (f->mults != nullptr) {
860  strncpy((char*)logstruct.multipliers, f->mults, LS_MULTIPLIERS_SIZE);
861  } else {
862  memset((char*)logstruct.multipliers, '\0', LS_MULTIPLIERS_SIZE);
863  memset((char*)logstruct.multipliers, '?', MIN(LS_MULTIPLIERS_SIZE, strlen(logstruct.format)));
864  // special magic to set units/mults for TimeUS, by far and
865  // away the most common first field
866  if (!strncmp(logstruct.labels, "TimeUS,", MIN(LS_LABELS_SIZE, strlen("TimeUS,")))) {
867  ((char*)(logstruct.units))[0] = 's';
868  ((char*)(logstruct.multipliers))[0] = 'F';
869  }
870  }
871  logstruct.msg_len = f->msg_len;
872  return true;
873 }
874 
875 /* calculate the length of output of a format string. Note that this
876  * returns an int16_t; if it returns -1 then an error has occurred.
877  * This was mechanically converted from init_field_types in
878  * Tools/Replay/MsgHandler.cpp */
880 {
881  uint8_t len = LOG_PACKET_HEADER_LEN;
882  for (uint8_t i=0; i<strlen(fmt); i++) {
883  switch(fmt[i]) {
884  case 'a' : len += sizeof(int16_t[32]); break;
885  case 'b' : len += sizeof(int8_t); break;
886  case 'c' : len += sizeof(int16_t); break;
887  case 'd' : len += sizeof(double); break;
888  case 'e' : len += sizeof(int32_t); break;
889  case 'f' : len += sizeof(float); break;
890  case 'h' : len += sizeof(int16_t); break;
891  case 'i' : len += sizeof(int32_t); break;
892  case 'n' : len += sizeof(char[4]); break;
893  case 'B' : len += sizeof(uint8_t); break;
894  case 'C' : len += sizeof(uint16_t); break;
895  case 'E' : len += sizeof(uint32_t); break;
896  case 'H' : len += sizeof(uint16_t); break;
897  case 'I' : len += sizeof(uint32_t); break;
898  case 'L' : len += sizeof(int32_t); break;
899  case 'M' : len += sizeof(uint8_t); break;
900  case 'N' : len += sizeof(char[16]); break;
901  case 'Z' : len += sizeof(char[64]); break;
902  case 'q' : len += sizeof(int64_t); break;
903  case 'Q' : len += sizeof(uint64_t); break;
904  default:
905 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
906  AP_HAL::panic("Unknown format specifier (%c)", fmt[i]);
907 #endif
908  return -1;
909  }
910  }
911  return len;
912 }
913 
914 /* End of Log_Write support */
915 
916 #undef FOR_EACH_BACKEND
917 
918 // Write information about a series of IMU readings to log:
919 bool DataFlash_Class::Log_Write_ISBH(const uint16_t seqno,
920  const AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
921  const uint8_t sensor_instance,
922  const uint16_t mult,
923  const uint16_t sample_count,
924  const uint64_t sample_us,
925  const float sample_rate_hz)
926 {
927  if (_next_backend == 0) {
928  return false;
929  }
930  struct log_ISBH pkt = {
933  seqno : seqno,
934  sensor_type : (uint8_t)sensor_type,
935  instance : sensor_instance,
936  multiplier : mult,
937  sample_count : sample_count,
938  sample_us : sample_us,
939  sample_rate_hz : sample_rate_hz,
940  };
941 
942  // only the first backend need succeed for us to be successful
943  for (uint8_t i=1; i<_next_backend; i++) {
944  backends[i]->WriteBlock(&pkt, sizeof(pkt));
945  }
946 
947  return backends[0]->WriteBlock(&pkt, sizeof(pkt));
948 }
949 
950 
951 // Write a series of IMU readings to log:
952 bool DataFlash_Class::Log_Write_ISBD(const uint16_t isb_seqno,
953  const uint16_t seqno,
954  const int16_t x[32],
955  const int16_t y[32],
956  const int16_t z[32])
957 {
958  if (_next_backend == 0) {
959  return false;
960  }
961  struct log_ISBD pkt = {
965  seqno : seqno
966  };
967  memcpy(pkt.x, x, sizeof(pkt.x));
968  memcpy(pkt.y, y, sizeof(pkt.y));
969  memcpy(pkt.z, z, sizeof(pkt.z));
970 
971  // only the first backend need succeed for us to be successful
972  for (uint8_t i=1; i<_next_backend; i++) {
973  backends[i]->WriteBlock(&pkt, sizeof(pkt));
974  }
975 
976  return backends[0]->WriteBlock(&pkt, sizeof(pkt));
977 }
int printf(const char *fmt,...)
Definition: stdio.c:113
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t *msg)
Definition: DataFlash.cpp:557
bool seen_ids[256]
Definition: DataFlash.h:325
void PrepForArming()
Definition: DataFlash.cpp:450
void Log_Write_MessageF(const char *fmt,...)
Definition: DataFlash.cpp:391
static const uint8_t LS_NAME_SIZE
Definition: LogStructure.h:28
void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
pretty-print field information from a log structure
Definition: DataFlash.cpp:209
const char * units
Definition: LogStructure.h:23
const char * name
Definition: LogStructure.h:20
static DataFlash_Class * _instance
Definition: DataFlash.h:310
uint8_t _next_backend
Definition: DataFlash.h:241
uint32_t num_dropped(void) const
int16_t find_free_msg_type() const
Definition: DataFlash.cpp:820
bool logging_enabled() const
Definition: DataFlash.cpp:365
struct log_write_fmt * next
Definition: DataFlash.h:257
struct log_write_fmt * msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
Definition: DataFlash.cpp:722
const uint8_t _num_multipliers
Definition: DataFlash.h:231
void internal_error() const
Definition: DataFlash.cpp:625
static const uint8_t LS_MULTIPLIERS_SIZE
Definition: LogStructure.h:32
int16_t y[32]
Definition: LogStructure.h:234
#define FALLTHROUGH
Definition: AP_Common.h:50
AP_HAL::UARTDriver * console
Definition: HAL.h:110
const char * multipliers
Definition: LogStructure.h:24
uint8_t msg_type
Definition: LogStructure.h:18
#define HAL_BOARD_LOG_DIRECTORY
Definition: linux.h:11
Interface definition for the various Ground Control System.
bool logging_started(void)
Definition: DataFlash.cpp:548
Object managing Mission.
Definition: AP_Mission.h:45
#define CHECK_ENTRY(fieldname, fieldname_s, fieldlen)
bool should_log(uint32_t mask) const
Definition: DataFlash.cpp:416
virtual void Init()
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
uint16_t isb_seqno
Definition: LogStructure.h:231
void Log_Write_Mode(uint8_t mode, uint8_t reason)
Definition: DataFlash.cpp:598
struct DataFlash_Class::@194 _params
void Log_Write_Message(const char *message)
Definition: DataFlash.cpp:593
virtual void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)=0
void Log_Write_Parameter(const char *name, float value)
Definition: DataFlash.cpp:603
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg)
AP_HAL::Util * util
Definition: HAL.h:115
#define DATAFLASH_MAX_BACKENDS
Definition: DataFlash.h:240
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
int16_t z[32]
Definition: LogStructure.h:235
GCS & gcs()
const char * format
Definition: LogStructure.h:21
const struct LogStructure * structure(uint16_t num) const
Definition: DataFlash.cpp:356
void WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
Definition: DataFlash.cpp:489
const uint8_t _num_units
Definition: DataFlash.h:230
const struct MultiplierStructure log_Multipliers[]
Definition: LogStructure.h:123
const char * name
Definition: BusTest.cpp:11
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
#define MIN(a, b)
Definition: usb_conf.h:215
const char * labels
Definition: LogStructure.h:22
bool in_log_download() const
Definition: DataFlash.h:219
bool Log_Write_ISBH(uint16_t seqno, AP_InertialSensor::IMU_SENSOR_TYPE sensor_type, uint8_t instance, uint16_t multiplier, uint16_t sample_count, uint64_t sample_us, float sample_rate_hz)
Definition: DataFlash.cpp:919
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
Definition: DataFlash.cpp:522
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)=0
void backend_starting_new_log(const DataFlash_Backend *backend)
Definition: DataFlash.cpp:403
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
Definition: DataFlash.cpp:835
#define x(i)
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
Definition: Util.cpp:53
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t sensor_type
Definition: LogStructure.h:219
void set_vehicle_armed(bool armed_state)
Definition: DataFlash.cpp:460
void Init(const struct LogStructure *structure, uint8_t num_types)
Definition: DataFlash.cpp:77
void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
Definition: DataFlash.cpp:216
AP_Int8 backend_types
Definition: DataFlash.h:196
const char * unit
Definition: LogStructure.h:70
static const struct AP_Param::GroupInfo var_info[]
Definition: DataFlash.h:194
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
virtual uint16_t find_last_log()=0
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
Definition: DataFlash.cpp:534
void Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list)
Definition: DataFlash.cpp:650
uint64_t time_us
Definition: LogStructure.h:217
#define streq(x, y)
Definition: DataFlash.cpp:63
#define f(i)
static uint8_t count_commas(const char *string)
return the number of commas present in string
Definition: DataFlash.cpp:174
const char * fmt
Definition: Printf.cpp:14
void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
Definition: DataFlash.cpp:339
const struct MultiplierStructure * _multipliers
Definition: DataFlash.h:229
void set_mission(const AP_Mission *mission)
Definition: DataFlash.cpp:476
bool msg_type_in_use(uint8_t msg_type) const
Definition: DataFlash.cpp:799
double multiplier_name(const uint8_t multiplier_id)
return a multiplier value given its ID
Definition: DataFlash.cpp:197
const AP_Int32 & _log_bitmask
Definition: DataFlash.h:244
bool log_while_disarmed(void) const
Definition: DataFlash.h:188
AP_Int8 file_bufsize
Definition: DataFlash.h:197
int16_t x[32]
Definition: LogStructure.h:233
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: DataFlash.cpp:170
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
Definition: DataFlash.cpp:528
uint64_t micros64()
Definition: system.cpp:162
static const uint8_t LS_LABELS_SIZE
Definition: LogStructure.h:30
uint16_t find_last_log() const
Definition: DataFlash.cpp:516
AP_Int8 log_replay
Definition: DataFlash.h:200
void periodic_tasks()
Definition: DataFlash.cpp:575
const struct MultiplierStructure * multiplier(uint16_t num) const
Definition: DataFlash.cpp:438
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
Definition: DataFlash.cpp:455
bool validate_structure(const struct LogStructure *logstructure, int16_t offset)
Definition: DataFlash.cpp:245
bool logging_failed() const
Definition: DataFlash.cpp:377
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:485
#define NULL
Definition: hal_types.h:59
uint16_t seqno
Definition: LogStructure.h:218
void Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
Definition: DataFlash.cpp:608
bool CardInserted(void)
Definition: DataFlash.cpp:498
virtual uint16_t get_num_logs()=0
bool logging_present() const
Definition: DataFlash.cpp:361
AP_Int32 log_bitmask
const struct UnitStructure * _units
Definition: DataFlash.h:228
const char * unit_name(const uint8_t unit_id)
return a unit name given its ID
Definition: DataFlash.cpp:186
void free(void *ptr)
Definition: malloc.c:81
uint8_t _num_types
Definition: DataFlash.h:227
bool Log_Write_ISBD(uint16_t isb_seqno, uint16_t seqno, const int16_t x[32], const int16_t y[32], const int16_t z[32])
Definition: DataFlash.cpp:952
#define Debug(fmt, args ...)
Definition: DataFlash.cpp:171
DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask)
Definition: DataFlash.cpp:65
void flush(void)
Definition: DataFlash.cpp:582
uint16_t seqno
Definition: LogStructure.h:232
static uint16_t log_num
bool passed
Definition: location.cpp:17
AP_Int8 log_disarmed
Definition: DataFlash.h:199
void assert_same_fmt_for_name(const log_write_fmt *f, const char *name, const char *labels, const char *units, const char *mults, const char *fmt) const
Definition: DataFlash.cpp:676
static const uint8_t LS_FORMAT_SIZE
Definition: LogStructure.h:29
void EnableWrites(bool enable)
Definition: DataFlash.h:90
const struct UnitStructure * unit(uint16_t num) const
Definition: DataFlash.cpp:433
const char * _firmware_string
Definition: DataFlash.h:243
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
uint64_t time_us
Definition: LogStructure.h:230
void StopLogging()
Definition: DataFlash.cpp:511
float value
void Log_Write_EntireMission(const AP_Mission &mission)
Definition: DataFlash.cpp:588
const double multiplier
Definition: LogStructure.h:75
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void uint32_t num
Definition: systick.h:80
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
bool WriteBlock(const void *pBuffer, uint16_t size)
vehicle_startup_message_Log_Writer _vehicle_messages
Definition: DataFlash.h:191
#define LOG_PACKET_HEADER_LEN
Definition: LogStructure.h:9
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)=0
static const uint8_t LS_UNITS_SIZE
Definition: LogStructure.h:31
uint8_t msg_len
Definition: LogStructure.h:19
const struct LogStructure * _structures
Definition: DataFlash.h:226
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_Int8 mav_bufsize
Definition: DataFlash.h:201
int16_t Log_Write_calc_msg_len(const char *fmt) const
Definition: DataFlash.cpp:879
bool vehicle_is_armed() const
Definition: DataFlash.h:216
uint16_t get_num_logs(void)
Definition: DataFlash.cpp:540
#define FOR_EACH_BACKEND(methodcall)
Definition: DataFlash.cpp:443
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
uint32_t num_dropped(void) const
Definition: DataFlash.cpp:614
DataFlash_Backend * backends[DATAFLASH_MAX_BACKENDS]
Definition: DataFlash.h:242
struct DataFlash_Class::log_write_fmt * log_write_fmts
AP_Int8 file_disarm_rot
Definition: DataFlash.h:198