APM:Libraries
DFMessageWriter.cpp
Go to the documentation of this file.
2 #include "DFMessageWriter.h"
3 
4 #define FORCE_VERSION_H_INCLUDE
5 #include "ap_version.h"
6 #undef FORCE_VERSION_H_INCLUDE
7 
8 extern const AP_HAL::HAL& hal;
9 
10 /* LogStartup - these are simple state machines which allow us to
11  * trickle out messages to the log files
12  */
13 
15 {
16  _finished = false;
17 }
18 
20 {
22 
23  _fmt_done = false;
24  _writesysinfo.reset();
25  _writeentiremission.reset();
26 
27  stage = ls_blockwriter_stage_init;
28  next_format_to_send = 0;
29  _next_unit_to_send = 0;
30  _next_multiplier_to_send = 0;
31  _next_format_unit_to_send = 0;
32  ap = AP_Param::first(&token, &type);
33 }
34 
36 {
37  switch(stage) {
38  case ls_blockwriter_stage_init:
39  stage = ls_blockwriter_stage_formats;
41 
42  case ls_blockwriter_stage_formats:
43  // write log formats so the log is self-describing
44  while (next_format_to_send < _dataflash_backend->num_types()) {
45  if (!_dataflash_backend->Log_Write_Format(_dataflash_backend->structure(next_format_to_send))) {
46  return; // call me again!
47  }
48  next_format_to_send++;
49  }
50  _fmt_done = true;
51  stage = ls_blockwriter_stage_parms;
53 
54  case ls_blockwriter_stage_units:
55  while (_next_unit_to_send < _dataflash_backend->num_units()) {
56  if (!_dataflash_backend->Log_Write_Unit(_dataflash_backend->unit(_next_unit_to_send))) {
57  return; // call me again!
58  }
59  _next_unit_to_send++;
60  }
61  stage = ls_blockwriter_stage_multipliers;
63 
64  case ls_blockwriter_stage_multipliers:
65  while (_next_multiplier_to_send < _dataflash_backend->num_multipliers()) {
66  if (!_dataflash_backend->Log_Write_Multiplier(_dataflash_backend->multiplier(_next_multiplier_to_send))) {
67  return; // call me again!
68  }
69  _next_multiplier_to_send++;
70  }
71  stage = ls_blockwriter_stage_units;
73 
74  case ls_blockwriter_stage_format_units:
75  while (_next_format_unit_to_send < _dataflash_backend->num_types()) {
76  if (!_dataflash_backend->Log_Write_Format_Units(_dataflash_backend->structure(_next_format_unit_to_send))) {
77  return; // call me again!
78  }
79  _next_format_unit_to_send++;
80  }
81  stage = ls_blockwriter_stage_parms;
83 
84  case ls_blockwriter_stage_parms:
85  while (ap) {
86  if (!_dataflash_backend->Log_Write_Parameter(ap, token, type)) {
87  return;
88  }
89  ap = AP_Param::next_scalar(&token, &type);
90  }
91 
92  stage = ls_blockwriter_stage_sysinfo;
94 
95  case ls_blockwriter_stage_sysinfo:
96  _writesysinfo.process();
97  if (!_writesysinfo.finished()) {
98  return;
99  }
100  stage = ls_blockwriter_stage_write_entire_mission;
101  FALLTHROUGH;
102 
103  case ls_blockwriter_stage_write_entire_mission:
104  _writeentiremission.process();
105  if (!_writeentiremission.finished()) {
106  return;
107  }
108  stage = ls_blockwriter_stage_vehicle_messages;
109  FALLTHROUGH;
110 
111  case ls_blockwriter_stage_vehicle_messages:
112  // we guarantee 200 bytes of space for the vehicle startup
113  // messages. This allows them to be simple functions rather
114  // than e.g. DFMessageWriter-based state machines
117  return;
118  }
120  }
121  stage = ls_blockwriter_stage_done;
122  FALLTHROUGH;
123 
124  case ls_blockwriter_stage_done:
125  break;
126  }
127 
128  _finished = true;
129 }
130 
132 {
134  stage = ws_blockwriter_stage_init;
135 }
136 
138 {
139  _writeentiremission.set_mission(mission);
140 }
141 
142 
144  switch(stage) {
145 
146  case ws_blockwriter_stage_init:
147  stage = ws_blockwriter_stage_firmware_string;
148  FALLTHROUGH;
149 
150  case ws_blockwriter_stage_firmware_string:
151  if (! _dataflash_backend->Log_Write_Message(_firmware_string)) {
152  return; // call me again
153  }
154  stage = ws_blockwriter_stage_git_versions;
155  FALLTHROUGH;
156 
157  case ws_blockwriter_stage_git_versions:
158 #if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
159  if (! _dataflash_backend->Log_Write_Message("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION)) {
160  return; // call me again
161  }
162 #endif
163  stage = ws_blockwriter_stage_system_id;
164  FALLTHROUGH;
165 
166  case ws_blockwriter_stage_system_id:
167  char sysid[40];
168  if (hal.util->get_system_id(sysid)) {
169  if (! _dataflash_backend->Log_Write_Message(sysid)) {
170  return; // call me again
171  }
172  }
173  }
174 
175  _finished = true; // all done!
176 }
177 
179  switch(stage) {
180 
181  case em_blockwriter_stage_init:
182  if (_mission == nullptr) {
183  stage = em_blockwriter_stage_done;
184  break;
185  } else {
186  stage = em_blockwriter_stage_write_new_mission_message;
187  }
188  FALLTHROUGH;
189 
190  case em_blockwriter_stage_write_new_mission_message:
191  if (! _dataflash_backend->Log_Write_Message("New mission")) {
192  return; // call me again
193  }
194  stage = em_blockwriter_stage_write_mission_items;
195  FALLTHROUGH;
196 
197  case em_blockwriter_stage_write_mission_items:
199  while (_mission_number_to_send < _mission->num_commands()) {
200  // upon failure to write the mission we will re-read from
201  // storage; this could be improved.
202  if (_mission->read_cmd_from_storage(_mission_number_to_send,cmd)) {
203  if (!_dataflash_backend->Log_Write_Mission_Cmd(*_mission, cmd)) {
204  return; // call me again
205  }
206  }
207  _mission_number_to_send++;
208  }
209  stage = em_blockwriter_stage_done;
210  FALLTHROUGH;
211 
212  case em_blockwriter_stage_done:
213  break;
214  }
215 
216  _finished = true;
217 }
218 
220 {
222  stage = em_blockwriter_stage_init;
223  _mission_number_to_send = 0;
224 }
225 
226 
228 {
229  _mission = mission;
230 }
bool Log_Write_Message(const char *message)
Definition: LogFile.cpp:426
virtual void reset()=0
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
#define FALLTHROUGH
Definition: AP_Common.h:50
bool Log_Write_Parameter(const char *name, float value)
Definition: LogFile.cpp:111
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1535
Object managing Mission.
Definition: AP_Mission.h:45
void set_mission(const AP_Mission *mission)
const struct UnitStructure * unit(uint8_t unit) const
AP_HAL::Util * util
Definition: HAL.h:115
bool Log_Write_Unit(const struct UnitStructure *s)
Definition: LogFile.cpp:70
bool Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
Definition: LogFile.cpp:409
const struct LogStructure * structure(uint8_t structure) const
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1387
virtual bool get_system_id(char buf[40])
Definition: Util.h:68
void set_mission(const AP_Mission *mission)
const struct MultiplierStructure * multiplier(uint8_t multiplier) const
virtual uint32_t bufferspace_available()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
DataFlash_Backend * _dataflash_backend
bool Log_Write_Multiplier(const struct MultiplierStructure *s)
Definition: LogFile.cpp:86