APM:Libraries
DataFlash_Backend.cpp
Go to the documentation of this file.
1 #include "DataFlash_Backend.h"
2 
3 #include "DFMessageWriter.h"
4 
5 extern const AP_HAL::HAL& hal;
6 
8  class DFMessageWriter_DFLogStart *writer) :
9  _front(front),
10  _startup_messagewriter(writer)
11 {
12  writer->set_dataflash_backend(this);
13 }
14 
16 {
17  return _front._num_types;
18 }
19 
20 const struct LogStructure *DataFlash_Backend::structure(uint8_t num) const
21 {
22  return _front.structure(num);
23 }
24 
26 {
27  return _front._num_units;
28 }
29 
30 const struct UnitStructure *DataFlash_Backend::unit(uint8_t num) const
31 {
32  return _front.unit(num);
33 }
34 
36 {
37  return _front._num_multipliers;
38 }
39 
41 {
42  return _front.multiplier(num);
43 }
44 
45 DataFlash_Backend::vehicle_startup_message_Log_Writer DataFlash_Backend::vehicle_message_writer() {
47 }
48 
49 void DataFlash_Backend::periodic_10Hz(const uint32_t now)
50 {
51 }
52 void DataFlash_Backend::periodic_1Hz(const uint32_t now)
53 {
54 }
55 void DataFlash_Backend::periodic_fullrate(const uint32_t now)
56 {
57 }
58 
60 {
61  uint32_t now = AP_HAL::millis();
62  if (now - _last_periodic_1Hz > 1000) {
63  periodic_1Hz(now);
64  _last_periodic_1Hz = now;
65  }
66  if (now - _last_periodic_10Hz > 100) {
67  periodic_10Hz(now);
68  _last_periodic_10Hz = now;
69  }
70  periodic_fullrate(now);
71 }
72 
74 {
77 }
78 
81 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
82  abort();
83 #endif
84 }
85 
88 }
89 
90 // this method can be overridden to do extra things with your buffer.
91 // for example, in DataFlash_MAVLink we may push messages into the UART.
94 }
95 
96 // returns true if all format messages have been written, and thus it is OK
97 // for other messages to go out to the log
99 {
101  return true;
102  }
103 
105  // we have been called by a messagewriter, so writing is OK
106  return true;
107  }
108 
110  !hal.scheduler->in_main_thread()) {
111  // only the main thread may write startup messages out
112  return false;
113  }
114 
115  // we're not writing startup messages, so this must be some random
116  // caller hoping to write blocks out. Push out log blocks - we
117  // might end up clearing the buffer.....
118  push_log_blocks();
119 
120  // even if we did finish writing startup messages, we can't
121  // permit any message to go in as its timestamp will be before
122  // any we wrote in. Time going backwards annoys log readers.
123 
124  // sorry! currently busy writing out startup messages...
125  return false;
126 }
127 
128 // source more messages from the startup message writer:
130 {
131 
133  return;
134  }
135 
139 }
140 
141 /*
142  * support for Log_Write():
143  */
144 
145 
147 {
148  // get log structure from front end:
149  char ls_name[LS_NAME_SIZE] = {};
150  char ls_format[LS_FORMAT_SIZE] = {};
151  char ls_labels[LS_LABELS_SIZE] = {};
152  char ls_units[LS_UNITS_SIZE] = {};
153  char ls_multipliers[LS_MULTIPLIERS_SIZE] = {};
154  struct LogStructure logstruct = {
155  // these will be overwritten, but need to keep the compiler happy:
156  0,
157  0,
158  ls_name,
159  ls_format,
160  ls_labels,
161  ls_units,
162  ls_multipliers
163  };
164  if (!_front.fill_log_write_logstructure(logstruct, msg_type)) {
165  // this is a bug; we've been asked to write out the FMT
166  // message for a msg_type, but the frontend can't supply the
167  // required information
168  internal_error();
169  return false;
170  }
171 
172  if (!Log_Write_Format(&logstruct)) {
173  return false;
174  }
175  if (!Log_Write_Format_Units(&logstruct)) {
176  return false;
177  }
178 
179  return true;
180 }
181 
182 bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool is_critical)
183 {
184  // stack-allocate a buffer so we can WriteBlock(); this could be
185  // 255 bytes! If we were willing to lose the WriteBlock
186  // abstraction we could do WriteBytes() here instead?
187  const char *fmt = nullptr;
188  uint8_t msg_len;
190  for (f = _front.log_write_fmts; f; f=f->next) {
191  if (f->msg_type == msg_type) {
192  fmt = f->fmt;
193  msg_len = f->msg_len;
194  break;
195  }
196  }
197  if (fmt == nullptr) {
198  // this is a bug.
199  internal_error();
200  return false;
201  }
202  if (bufferspace_available() < msg_len) {
203  return false;
204  }
205  uint8_t buffer[msg_len];
206  uint8_t offset = 0;
207  buffer[offset++] = HEAD_BYTE1;
208  buffer[offset++] = HEAD_BYTE2;
209  buffer[offset++] = msg_type;
210  for (uint8_t i=0; i<strlen(fmt); i++) {
211  uint8_t charlen = 0;
212  switch(fmt[i]) {
213  case 'b': {
214  int8_t tmp = va_arg(arg_list, int);
215  memcpy(&buffer[offset], &tmp, sizeof(int8_t));
216  offset += sizeof(int8_t);
217  break;
218  }
219  case 'h':
220  case 'c': {
221  int16_t tmp = va_arg(arg_list, int);
222  memcpy(&buffer[offset], &tmp, sizeof(int16_t));
223  offset += sizeof(int16_t);
224  break;
225  }
226  case 'd': {
227  double tmp = va_arg(arg_list, double);
228  memcpy(&buffer[offset], &tmp, sizeof(double));
229  offset += sizeof(double);
230  break;
231  }
232  case 'i':
233  case 'L':
234  case 'e': {
235  int32_t tmp = va_arg(arg_list, int);
236  memcpy(&buffer[offset], &tmp, sizeof(int32_t));
237  offset += sizeof(int32_t);
238  break;
239  }
240  case 'f': {
241  float tmp = va_arg(arg_list, double);
242  memcpy(&buffer[offset], &tmp, sizeof(float));
243  offset += sizeof(float);
244  break;
245  }
246  case 'n':
247  charlen = 4;
248  break;
249  case 'M':
250  case 'B': {
251  uint8_t tmp = va_arg(arg_list, int);
252  memcpy(&buffer[offset], &tmp, sizeof(uint8_t));
253  offset += sizeof(uint8_t);
254  break;
255  }
256  case 'H':
257  case 'C': {
258  uint16_t tmp = va_arg(arg_list, int);
259  memcpy(&buffer[offset], &tmp, sizeof(uint16_t));
260  offset += sizeof(uint16_t);
261  break;
262  }
263  case 'I':
264  case 'E': {
265  uint32_t tmp = va_arg(arg_list, uint32_t);
266  memcpy(&buffer[offset], &tmp, sizeof(uint32_t));
267  offset += sizeof(uint32_t);
268  break;
269  }
270  case 'N':
271  charlen = 16;
272  break;
273  case 'Z':
274  charlen = 64;
275  break;
276  case 'q': {
277  int64_t tmp = va_arg(arg_list, int64_t);
278  memcpy(&buffer[offset], &tmp, sizeof(int64_t));
279  offset += sizeof(int64_t);
280  break;
281  }
282  case 'Q': {
283  uint64_t tmp = va_arg(arg_list, uint64_t);
284  memcpy(&buffer[offset], &tmp, sizeof(uint64_t));
285  offset += sizeof(uint64_t);
286  break;
287  }
288  }
289  if (charlen != 0) {
290  char *tmp = va_arg(arg_list, char*);
291  memcpy(&buffer[offset], tmp, charlen);
292  offset += charlen;
293  }
294  }
295 
296  return WritePrioritisedBlock(buffer, msg_len, is_critical);
297 }
298 
300 {
301  if (logging_started()) {
302  return false;
303  }
304  if (_front._log_bitmask == 0) {
305  return false;
306  }
307  if (_front.in_log_download()) {
308  return false;
309  }
310  if (!hal.scheduler->in_main_thread()) {
311  return false;
312  }
313  return true;
314 }
315 
316 bool DataFlash_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
317 {
318  if (!ShouldLog(is_critical)) {
319  return false;
320  }
321  if (StartNewLogOK()) {
322  start_new_log();
323  }
324  if (!WritesOK()) {
325  return false;
326  }
327  return _WritePrioritisedBlock(pBuffer, size, is_critical);
328 }
329 
330 bool DataFlash_Backend::ShouldLog(bool is_critical)
331 {
332  if (!_front.WritesEnabled()) {
333  return false;
334  }
335  if (!_initialised) {
336  return false;
337  }
338 
340  !hal.scheduler->in_main_thread()) {
341  // only the main thread may write startup messages out
342  return false;
343  }
344 
345  if (is_critical && have_logged_armed && !_front._params.file_disarm_rot) {
346  // if we have previously logged while armed then we log all
347  // critical messages from then on. That fixes a problem where
348  // logs show the wrong flight mode if you disarm then arm again
349  return true;
350  }
351 
353  return false;
354  }
355 
356  if (_front.vehicle_is_armed()) {
357  have_logged_armed = true;
358  }
359 
360  return true;
361 }
static const uint8_t LS_NAME_SIZE
Definition: LogStructure.h:28
virtual void WriteMoreStartupMessages()
bool Log_Write_Emit_FMT(uint8_t msg_type)
struct log_write_fmt * next
Definition: DataFlash.h:257
DFMessageWriter_DFLogStart * _startup_messagewriter
const uint8_t _num_multipliers
Definition: DataFlash.h:231
vehicle_startup_message_Log_Writer vehicle_message_writer()
static const uint8_t LS_MULTIPLIERS_SIZE
Definition: LogStructure.h:32
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 StartNewLogOK() const
uint8_t msg_type
Definition: LogStructure.h:18
virtual void periodic_tasks()
virtual void start_new_log_reset_variables()
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
Object managing Mission.
Definition: AP_Mission.h:45
void set_mission(const AP_Mission *mission)
struct DataFlash_Class::@194 _params
virtual bool in_main_thread() const =0
const struct UnitStructure * unit(uint8_t unit) const
uint8_t num_units() const
const struct LogStructure * structure(uint16_t num) const
Definition: DataFlash.cpp:356
uint8_t num_multipliers() const
const struct LogStructure * structure(uint8_t structure) const
const uint8_t _num_units
Definition: DataFlash.h:230
bool in_log_download() const
Definition: DataFlash.h:219
virtual void set_dataflash_backend(class DataFlash_Backend *backend)
void backend_starting_new_log(const DataFlash_Backend *backend)
Definition: DataFlash.cpp:403
virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)=0
#define HEAD_BYTE1
Definition: LogStructure.h:13
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
Definition: DataFlash.cpp:835
virtual bool WritesOK() const =0
virtual bool WriteBlockCheckStartupMessages()
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
#define f(i)
const char * fmt
Definition: Printf.cpp:14
uint32_t millis()
Definition: system.cpp:157
const AP_Int32 & _log_bitmask
Definition: DataFlash.h:244
bool log_while_disarmed(void) const
Definition: DataFlash.h:188
virtual void periodic_10Hz(const uint32_t now)
virtual void periodic_fullrate(const uint32_t now)
static const uint8_t LS_LABELS_SIZE
Definition: LogStructure.h:30
bool WritesEnabled() const
Definition: DataFlash.h:91
void set_mission(const AP_Mission *mission)
const struct MultiplierStructure * multiplier(uint16_t num) const
Definition: DataFlash.cpp:438
const struct MultiplierStructure * multiplier(uint8_t multiplier) const
DataFlash_Backend(DataFlash_Class &front, class DFMessageWriter_DFLogStart *writer)
uint8_t _num_types
Definition: DataFlash.h:227
DataFlash_Class & _front
bool ShouldLog(bool is_critical)
virtual void periodic_1Hz(const uint32_t now)
static const uint8_t LS_FORMAT_SIZE
Definition: LogStructure.h:29
virtual uint32_t bufferspace_available()=0
const struct UnitStructure * unit(uint16_t num) const
Definition: DataFlash.cpp:433
virtual uint16_t start_new_log(void)=0
void uint32_t num
Definition: systick.h:80
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
vehicle_startup_message_Log_Writer _vehicle_messages
Definition: DataFlash.h:191
virtual bool finished()
static const uint8_t LS_UNITS_SIZE
Definition: LogStructure.h:31
uint8_t msg_len
Definition: LogStructure.h:19
virtual void push_log_blocks()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool vehicle_is_armed() const
Definition: DataFlash.h:216
virtual bool logging_started(void) const =0
#define HEAD_BYTE2
Definition: LogStructure.h:14
struct DataFlash_Class::log_write_fmt * log_write_fmts
AP_Int8 file_disarm_rot
Definition: DataFlash.h:198