4 #define FORCE_VERSION_H_INCLUDE 6 #undef FORCE_VERSION_H_INCLUDE 24 _writesysinfo.reset();
25 _writeentiremission.reset();
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;
38 case ls_blockwriter_stage_init:
39 stage = ls_blockwriter_stage_formats;
42 case ls_blockwriter_stage_formats:
44 while (next_format_to_send < _dataflash_backend->num_types()) {
48 next_format_to_send++;
51 stage = ls_blockwriter_stage_parms;
54 case ls_blockwriter_stage_units:
55 while (_next_unit_to_send < _dataflash_backend->num_units()) {
61 stage = ls_blockwriter_stage_multipliers;
64 case ls_blockwriter_stage_multipliers:
65 while (_next_multiplier_to_send < _dataflash_backend->num_multipliers()) {
69 _next_multiplier_to_send++;
71 stage = ls_blockwriter_stage_units;
74 case ls_blockwriter_stage_format_units:
75 while (_next_format_unit_to_send < _dataflash_backend->num_types()) {
79 _next_format_unit_to_send++;
81 stage = ls_blockwriter_stage_parms;
84 case ls_blockwriter_stage_parms:
92 stage = ls_blockwriter_stage_sysinfo;
95 case ls_blockwriter_stage_sysinfo:
96 _writesysinfo.process();
97 if (!_writesysinfo.finished()) {
100 stage = ls_blockwriter_stage_write_entire_mission;
103 case ls_blockwriter_stage_write_entire_mission:
104 _writeentiremission.process();
105 if (!_writeentiremission.finished()) {
108 stage = ls_blockwriter_stage_vehicle_messages;
111 case ls_blockwriter_stage_vehicle_messages:
121 stage = ls_blockwriter_stage_done;
124 case ls_blockwriter_stage_done:
134 stage = ws_blockwriter_stage_init;
139 _writeentiremission.set_mission(mission);
146 case ws_blockwriter_stage_init:
147 stage = ws_blockwriter_stage_firmware_string;
150 case ws_blockwriter_stage_firmware_string:
154 stage = ws_blockwriter_stage_git_versions;
157 case ws_blockwriter_stage_git_versions:
158 #if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION) 163 stage = ws_blockwriter_stage_system_id;
166 case ws_blockwriter_stage_system_id:
181 case em_blockwriter_stage_init:
182 if (_mission ==
nullptr) {
183 stage = em_blockwriter_stage_done;
186 stage = em_blockwriter_stage_write_new_mission_message;
190 case em_blockwriter_stage_write_new_mission_message:
194 stage = em_blockwriter_stage_write_mission_items;
197 case em_blockwriter_stage_write_mission_items:
199 while (_mission_number_to_send < _mission->num_commands()) {
202 if (_mission->read_cmd_from_storage(_mission_number_to_send,cmd)) {
207 _mission_number_to_send++;
209 stage = em_blockwriter_stage_done;
212 case em_blockwriter_stage_done:
222 stage = em_blockwriter_stage_init;
223 _mission_number_to_send = 0;
bool Log_Write_Message(const char *message)
vehicle_startup_message_Log_Writer vehicle_message_writer()
bool Log_Write_Format_Units(const struct LogStructure *structure)
bool Log_Write_Format(const struct LogStructure *structure)
bool Log_Write_Parameter(const char *name, float value)
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype)
void set_mission(const AP_Mission *mission)
const struct UnitStructure * unit(uint8_t unit) const
bool Log_Write_Unit(const struct UnitStructure *s)
bool Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
const struct LogStructure * structure(uint8_t structure) const
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype)
virtual bool get_system_id(char buf[40])
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 -*-
DataFlash_Backend * _dataflash_backend
bool Log_Write_Multiplier(const struct MultiplierStructure *s)