AP_Logger_Backend.h 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166
  1. #pragma once
  2. #include "AP_Logger.h"
  3. class LoggerMessageWriter_DFLogStart;
  4. class AP_Logger_Backend
  5. {
  6. public:
  7. FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void);
  8. AP_Logger_Backend(AP_Logger &front,
  9. class LoggerMessageWriter_DFLogStart *writer);
  10. vehicle_startup_message_Writer vehicle_message_writer();
  11. virtual bool CardInserted(void) const = 0;
  12. // erase handling
  13. virtual void EraseAll() = 0;
  14. virtual bool NeedPrep() = 0;
  15. virtual void Prep() = 0;
  16. /* Write a block of data at current offset */
  17. bool WriteBlock(const void *pBuffer, uint16_t size) {
  18. return WritePrioritisedBlock(pBuffer, size, false);
  19. }
  20. bool WriteCriticalBlock(const void *pBuffer, uint16_t size) {
  21. return WritePrioritisedBlock(pBuffer, size, true);
  22. }
  23. bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
  24. // high level interface
  25. virtual uint16_t find_last_log() = 0;
  26. virtual void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) = 0;
  27. virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
  28. virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
  29. virtual uint16_t get_num_logs() = 0;
  30. virtual bool logging_started(void) const = 0;
  31. virtual void Init() { }
  32. virtual uint32_t bufferspace_available() = 0;
  33. virtual void PrepForArming() { }
  34. virtual uint16_t start_new_log(void) = 0;
  35. /* stop logging - close output files etc etc.
  36. *
  37. * note that this doesn't stop logging from starting up again
  38. * immediately - e.g. AP_Logger_MAVLink might get another start
  39. * packet from a client.
  40. */
  41. virtual void stop_logging(void) = 0;
  42. void Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
  43. void Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt);
  44. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  45. // currently only AP_Logger_File support this:
  46. virtual void flush(void) { }
  47. #endif
  48. // for Logger_MAVlink
  49. virtual void remote_log_block_status_msg(const mavlink_channel_t chan,
  50. const mavlink_message_t &msg) { }
  51. // end for Logger_MAVlink
  52. virtual void periodic_tasks();
  53. uint8_t num_types() const;
  54. const struct LogStructure *structure(uint8_t structure) const;
  55. uint8_t num_units() const;
  56. const struct UnitStructure *unit(uint8_t unit) const;
  57. uint8_t num_multipliers() const;
  58. const struct MultiplierStructure *multiplier(uint8_t multiplier) const;
  59. void Write_EntireMission();
  60. bool Write_RallyPoint(uint8_t total,
  61. uint8_t sequence,
  62. const RallyLocation &rally_point);
  63. void Write_Rally();
  64. bool Write_Format(const struct LogStructure *structure);
  65. bool Write_Message(const char *message);
  66. bool Write_MessageF(const char *fmt, ...);
  67. bool Write_Mission_Cmd(const AP_Mission &mission,
  68. const AP_Mission::Mission_Command &cmd);
  69. bool Write_Mode(uint8_t mode, uint8_t reason = 0);
  70. bool Write_Parameter(const char *name, float value);
  71. bool Write_Parameter(const AP_Param *ap,
  72. const AP_Param::ParamToken &token,
  73. enum ap_var_type type);
  74. uint32_t num_dropped(void) const {
  75. return _dropped;
  76. }
  77. /*
  78. * Write support
  79. */
  80. // write a FMT message out (if it hasn't been done already).
  81. // Returns true if the FMT message has ever been written.
  82. bool Write_Emit_FMT(uint8_t msg_type);
  83. // write a log message out to the log of msg_type type, with
  84. // values contained in arg_list:
  85. bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false);
  86. // these methods are used when reporting system status over mavlink
  87. virtual bool logging_enabled() const = 0;
  88. virtual bool logging_failed() const = 0;
  89. virtual void vehicle_was_disarmed() { };
  90. bool Write_Unit(const struct UnitStructure *s);
  91. bool Write_Multiplier(const struct MultiplierStructure *s);
  92. bool Write_Format_Units(const struct LogStructure *structure);
  93. protected:
  94. AP_Logger &_front;
  95. virtual void periodic_10Hz(const uint32_t now);
  96. virtual void periodic_1Hz();
  97. virtual void periodic_fullrate();
  98. bool ShouldLog(bool is_critical);
  99. virtual bool WritesOK() const = 0;
  100. virtual bool StartNewLogOK() const;
  101. /*
  102. read a block
  103. */
  104. virtual bool WriteBlockCheckStartupMessages();
  105. virtual void WriteMoreStartupMessages();
  106. virtual void push_log_blocks();
  107. LoggerMessageWriter_DFLogStart *_startup_messagewriter;
  108. bool _writing_startup_messages;
  109. uint32_t _dropped;
  110. // must be called when a new log is being started:
  111. virtual void start_new_log_reset_variables();
  112. virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;
  113. bool _initialised;
  114. private:
  115. uint32_t _last_periodic_1Hz;
  116. uint32_t _last_periodic_10Hz;
  117. bool have_logged_armed;
  118. void validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size);
  119. };