DataFlash: use FALLTHROUGH define
When falling through on a case switch, allow to add an empty statement with the correct attribute to tell the compiler this behavior is intended.
This commit is contained in:
parent
7b0d6166e1
commit
927289aa64
@ -30,7 +30,7 @@ void DFMessageWriter_DFLogStart::process()
|
||||
switch(stage) {
|
||||
case ls_blockwriter_stage_init:
|
||||
stage = ls_blockwriter_stage_formats;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ls_blockwriter_stage_formats:
|
||||
// write log formats so the log is self-describing
|
||||
@ -42,7 +42,7 @@ void DFMessageWriter_DFLogStart::process()
|
||||
}
|
||||
_fmt_done = true;
|
||||
stage = ls_blockwriter_stage_parms;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ls_blockwriter_stage_parms:
|
||||
while (ap) {
|
||||
@ -53,7 +53,7 @@ void DFMessageWriter_DFLogStart::process()
|
||||
}
|
||||
|
||||
stage = ls_blockwriter_stage_sysinfo;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ls_blockwriter_stage_sysinfo:
|
||||
_writesysinfo.process();
|
||||
@ -61,7 +61,7 @@ void DFMessageWriter_DFLogStart::process()
|
||||
return;
|
||||
}
|
||||
stage = ls_blockwriter_stage_write_entire_mission;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ls_blockwriter_stage_write_entire_mission:
|
||||
_writeentiremission.process();
|
||||
@ -69,7 +69,7 @@ void DFMessageWriter_DFLogStart::process()
|
||||
return;
|
||||
}
|
||||
stage = ls_blockwriter_stage_vehicle_messages;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ls_blockwriter_stage_vehicle_messages:
|
||||
// we guarantee 200 bytes of space for the vehicle startup
|
||||
@ -82,7 +82,7 @@ void DFMessageWriter_DFLogStart::process()
|
||||
(_dataflash_backend->vehicle_message_writer())();
|
||||
}
|
||||
stage = ls_blockwriter_stage_done;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ls_blockwriter_stage_done:
|
||||
break;
|
||||
@ -108,14 +108,14 @@ void DFMessageWriter_WriteSysInfo::process() {
|
||||
|
||||
case ws_blockwriter_stage_init:
|
||||
stage = ws_blockwriter_stage_firmware_string;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ws_blockwriter_stage_firmware_string:
|
||||
if (! _dataflash_backend->Log_Write_Message(_firmware_string)) {
|
||||
return; // call me again
|
||||
}
|
||||
stage = ws_blockwriter_stage_git_versions;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ws_blockwriter_stage_git_versions:
|
||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||
@ -124,7 +124,7 @@ void DFMessageWriter_WriteSysInfo::process() {
|
||||
}
|
||||
#endif
|
||||
stage = ws_blockwriter_stage_system_id;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case ws_blockwriter_stage_system_id:
|
||||
char sysid[40];
|
||||
@ -133,7 +133,7 @@ void DFMessageWriter_WriteSysInfo::process() {
|
||||
return; // call me again
|
||||
}
|
||||
}
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
}
|
||||
|
||||
_finished = true; // all done!
|
||||
@ -149,14 +149,14 @@ void DFMessageWriter_WriteEntireMission::process() {
|
||||
} else {
|
||||
stage = em_blockwriter_stage_write_new_mission_message;
|
||||
}
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case em_blockwriter_stage_write_new_mission_message:
|
||||
if (! _dataflash_backend->Log_Write_Message("New mission")) {
|
||||
return; // call me again
|
||||
}
|
||||
stage = em_blockwriter_stage_write_mission_items;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case em_blockwriter_stage_write_mission_items:
|
||||
AP_Mission::Mission_Command cmd;
|
||||
@ -171,7 +171,7 @@ void DFMessageWriter_WriteEntireMission::process() {
|
||||
_mission_number_to_send++;
|
||||
}
|
||||
stage = em_blockwriter_stage_done;
|
||||
// no break
|
||||
FALLTHROUGH;
|
||||
|
||||
case em_blockwriter_stage_done:
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user