APM:Libraries
DataFlash_Backend.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "DataFlash.h"
4 
6 
8 {
9 
10 public:
11  FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
12 
14  class DFMessageWriter_DFLogStart *writer);
15 
16  vehicle_startup_message_Log_Writer vehicle_message_writer();
17 
18  void internal_error();
19 
20  virtual bool CardInserted(void) const = 0;
21 
22  // erase handling
23  virtual void EraseAll() = 0;
24 
25  virtual bool NeedPrep() = 0;
26  virtual void Prep() = 0;
27 
28  /* Write a block of data at current offset */
29  bool WriteBlock(const void *pBuffer, uint16_t size) {
30  return WritePrioritisedBlock(pBuffer, size, false);
31  }
32 
33  bool WriteCriticalBlock(const void *pBuffer, uint16_t size) {
34  return WritePrioritisedBlock(pBuffer, size, true);
35  }
36 
37  bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
38 
39  // high level interface
40  virtual uint16_t find_last_log() = 0;
41  virtual void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
42  virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
43  virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
44  virtual uint16_t get_num_logs() = 0;
45 
46  virtual bool logging_started(void) const = 0;
47 
48  virtual void Init() { }
49 
50  void set_mission(const AP_Mission *mission);
51 
52  virtual uint32_t bufferspace_available() = 0;
53 
54  virtual void PrepForArming() { }
55 
56  virtual uint16_t start_new_log(void) = 0;
57 
58  /* stop logging - close output files etc etc.
59  *
60  * note that this doesn't stop logging from starting up again
61  * immediately - e.g. DataFlash_MAVLink might get another start
62  * packet from a client.
63  */
64  virtual void stop_logging(void) = 0;
65 
66  void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
67  void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt);
68 
69 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
70  // currently only DataFlash_File support this:
71  virtual void flush(void) { }
72 #endif
73 
74  // for Dataflash_MAVlink
75  virtual void remote_log_block_status_msg(mavlink_channel_t chan,
76  mavlink_message_t* msg) { }
77  // end for Dataflash_MAVlink
78 
79  virtual void periodic_tasks();
80 
81  uint8_t num_types() const;
82  const struct LogStructure *structure(uint8_t structure) const;
83 
84  uint8_t num_units() const;
85  const struct UnitStructure *unit(uint8_t unit) const;
86 
87  uint8_t num_multipliers() const;
88  const struct MultiplierStructure *multiplier(uint8_t multiplier) const;
89 
90  void Log_Write_EntireMission(const AP_Mission &mission);
91  bool Log_Write_Format(const struct LogStructure *structure);
92  bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
93  bool Log_Write_Message(const char *message);
94  bool Log_Write_Mission_Cmd(const AP_Mission &mission,
95  const AP_Mission::Mission_Command &cmd);
96  bool Log_Write_Mode(uint8_t mode, uint8_t reason = 0);
97  bool Log_Write_Parameter(const char *name, float value);
98  bool Log_Write_Parameter(const AP_Param *ap,
99  const AP_Param::ParamToken &token,
100  enum ap_var_type type);
101 
102  uint32_t num_dropped(void) const {
103  return _dropped;
104  }
105 
106  /*
107  * Log_Write support
108  */
109  // write a FMT message out (if it hasn't been done already).
110  // Returns true if the FMT message has ever been written.
111  bool Log_Write_Emit_FMT(uint8_t msg_type);
112 
113  // write a log message out to the log of msg_type type, with
114  // values contained in arg_list:
115  bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false);
116 
117  // these methods are used when reporting system status over mavlink
118  virtual bool logging_enabled() const = 0;
119  virtual bool logging_failed() const = 0;
120 
121  virtual void vehicle_was_disarmed() { };
122 
123  bool Log_Write_Unit(const struct UnitStructure *s);
124  bool Log_Write_Multiplier(const struct MultiplierStructure *s);
125  bool Log_Write_Format_Units(const struct LogStructure *structure);
126 
127 
128 protected:
129 
131 
132  virtual void periodic_10Hz(const uint32_t now);
133  virtual void periodic_1Hz(const uint32_t now);
134  virtual void periodic_fullrate(const uint32_t now);
135 
136  bool ShouldLog(bool is_critical);
137  virtual bool WritesOK() const = 0;
138  virtual bool StartNewLogOK() const;
139 
140  /*
141  read a block
142  */
143  virtual bool ReadBlock(void *pkt, uint16_t size) = 0;
144 
145  virtual bool WriteBlockCheckStartupMessages();
146  virtual void WriteMoreStartupMessages();
147  virtual void push_log_blocks();
148 
151 
153  uint32_t _dropped;
154 
155  // must be called when a new log is being started:
156  virtual void start_new_log_reset_variables();
157 
158  virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;
159 
161 
162 private:
163 
167 };
virtual void stop_logging(void)=0
virtual void WriteMoreStartupMessages()
bool Log_Write_Message(const char *message)
Definition: LogFile.cpp:426
uint32_t num_dropped(void) const
bool Log_Write_Emit_FMT(uint8_t msg_type)
DFMessageWriter_DFLogStart * _startup_messagewriter
ap_var_type
Definition: AP_Param.h:124
vehicle_startup_message_Log_Writer vehicle_message_writer()
bool Log_Write_Format_Units(const struct LogStructure *structure)
Definition: LogFile.cpp:101
bool Log_Write_Format(const struct LogStructure *structure)
Definition: LogFile.cpp:60
uint8_t num_types() const
virtual bool CardInserted(void) const =0
bool Log_Write_Parameter(const char *name, float value)
Definition: LogFile.cpp:111
virtual bool StartNewLogOK() const
virtual void periodic_tasks()
virtual void start_new_log_reset_variables()
Object managing Mission.
Definition: AP_Mission.h:45
virtual void Init()
bool WriteCriticalBlock(const void *pBuffer, uint16_t size)
virtual void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)=0
const struct UnitStructure * unit(uint8_t unit) const
uint8_t num_units() const
bool Log_Write_Unit(const struct UnitStructure *s)
Definition: LogFile.cpp:70
uint8_t num_multipliers() const
bool Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
Definition: LogFile.cpp:409
virtual void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t *msg)
const struct LogStructure * structure(uint8_t structure) const
const char * name
Definition: BusTest.cpp:11
virtual void vehicle_was_disarmed()
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd)
Definition: LogFile.cpp:1276
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)=0
virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)=0
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void)
virtual void flush(void)
virtual bool WritesOK() const =0
virtual uint16_t find_last_log()=0
virtual bool WriteBlockCheckStartupMessages()
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
Definition: LogFile.cpp:45
virtual void EraseAll()=0
virtual void periodic_10Hz(const uint32_t now)
virtual void periodic_fullrate(const uint32_t now)
virtual bool logging_enabled() const =0
void set_mission(const AP_Mission *mission)
virtual bool logging_failed() const =0
virtual void Prep()=0
const struct MultiplierStructure * multiplier(uint8_t multiplier) const
DataFlash_Backend(DataFlash_Class &front, class DFMessageWriter_DFLogStart *writer)
void Log_Write_EntireMission(const AP_Mission &mission)
Definition: LogFile.cpp:417
virtual uint16_t get_num_logs()=0
DataFlash_Class & _front
bool ShouldLog(bool is_critical)
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt)
Definition: LogFile.cpp:29
static uint16_t log_num
virtual void periodic_1Hz(const uint32_t now)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
virtual uint32_t bufferspace_available()=0
virtual void PrepForArming()
float value
virtual uint16_t start_new_log(void)=0
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
bool WriteBlock(const void *pBuffer, uint16_t size)
virtual bool NeedPrep()=0
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)=0
virtual void push_log_blocks()
bool Log_Write_Multiplier(const struct MultiplierStructure *s)
Definition: LogFile.cpp:86
virtual bool logging_started(void) const =0
bool Log_Write_Mode(uint8_t mode, uint8_t reason=0)
Definition: LogFile.cpp:1496
virtual bool ReadBlock(void *pkt, uint16_t size)=0