Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

waf: make implicit fallthroughs fatal #13202

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduCopter/mode_althold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ void ModeAltHold::run()

case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH
FALLTHROUGH;

case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_flowhold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,7 @@ void ModeFlowHold::run()

case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH
FALLTHROUGH;

case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_loiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ void ModeLoiter::run()

case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH
FALLTHROUGH;

case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ void ModePosHold::run()
loiter_nav->init_target();
loiter_nav->update();
attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH
FALLTHROUGH;

case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_sport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ void ModeSport::run()

case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH
FALLTHROUGH;

case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms();
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/mode_stabilize_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ void ModeStabilize_Heli::run()
if (!motors->limit.throttle_lower) {
set_land_complete(false);
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing
Expand Down
18 changes: 16 additions & 2 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,11 @@ def configure(self, cfg):
cfg.srcnode.find_dir('libraries/AP_Common/missing').abspath()
])

def cc_version_gte(self, cfg, want_major, want_minor):
(major, minor, patchlevel) = cfg.env.CC_VERSION
return (int(major) > want_major or
(int(major) == want_major and int(minor) >= want_minor))

def configure_env(self, cfg, env):
# Use a dictionary instead of the convetional list for definitions to
# make easy to override them. Convert back to list before consumption.
Expand Down Expand Up @@ -140,11 +145,16 @@ def configure_env(self, cfg, env):
'-Wno-inconsistent-missing-override',
'-Wno-mismatched-tags',
'-Wno-gnu-variable-sized-type-not-at-end',
'-Werror=implicit-fallthrough',
]
else:
env.CFLAGS += [
'-Wno-format-contains-nul',
]
if self.cc_version_gte(cfg, 7, 4):
env.CXXFLAGS += [
'-Werror=implicit-fallthrough',
]

if cfg.env.DEBUG:
env.CFLAGS += [
Expand Down Expand Up @@ -227,17 +237,21 @@ def configure_env(self, cfg, env):
'-Wno-gnu-designator',
'-Wno-mismatched-tags',
'-Wno-gnu-variable-sized-type-not-at-end',
'-Werror=implicit-fallthrough',
]
else:
env.CXXFLAGS += [
'-Wno-format-contains-nul',
'-Werror=unused-but-set-variable'
]
(major, minor, patchlevel) = cfg.env.CC_VERSION
if int(major) > 5 or (int(major) == 5 and int(minor) > 1):
if self.cc_version_gte(cfg, 5, 2):
env.CXXFLAGS += [
'-Werror=suggest-override',
]
if self.cc_version_gte(cfg, 7, 4):
env.CXXFLAGS += [
'-Werror=implicit-fallthrough',
]

if cfg.env.DEBUG:
env.CXXFLAGS += [
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_ADSB/AP_ADSB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -938,6 +938,8 @@ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle)
if (!is_special_vehicle(vehicle.info.ICAO_address)) {
return;
}
break;

case logging::ALL:
break;

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)
case AP_Airspeed::PITOT_TUBE_ORDER_NEGATIVE:
press = -press;
sign = -1.0f;
//FALLTHROUGH;
break;
case AP_Airspeed::PITOT_TUBE_ORDER_POSITIVE:
break;
case AP_Airspeed::PITOT_TUBE_ORDER_AUTO:
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Baro/AP_Baro_BMP085.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -335,6 +335,7 @@ bool AP_Baro_BMP085::_data_ready()
break;
case BMP085_OVERSAMPLING_ULTRAHIGHRES:
conversion_time_msec = 26;
break;
default:
break;
}
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL/utility/dsm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,6 +281,7 @@ dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, u

case 2:
channel = 1;
break;

default:
break;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,7 @@ bool AP_RCProtocol_DSM::dsm_decode(uint32_t frame_time_ms, const uint8_t dsm_fra

case 2:
channel = 1;
break;

default:
break;
Expand Down