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

Tools: waf: add various conversion warning compiler options #11094

Merged
merged 6 commits into from
Apr 29, 2019
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
3 changes: 3 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,9 @@ matrix:
- if: type != cron
compiler: "clang-7"
env: CI_BUILD_TARGET="sitltest-rover sitltest-sub""
- if: type != cron
compiler: "clang-7"
env: CI_BUILD_TARGET="sitl""
- language: python
python: 3.7
addons: # speedup: This test does not need addons
Expand Down
26 changes: 13 additions & 13 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ bool AP_Arming_Copter::all_checks_passing(AP_Arming::Method method)
{
set_pre_arm_check(pre_arm_checks(true));

return copter.ap.pre_arm_check && arm_checks(true, method);
return copter.ap.pre_arm_check && arm_checks(method);
}

// perform pre-arm checks
Expand Down Expand Up @@ -439,21 +439,21 @@ bool AP_Arming_Copter::pre_arm_proximity_check(bool display_failure)
// arm_checks - perform final checks before arming
// always called just before arming. Return true if ok to arm
// has side-effect that logging is started
bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method)
bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
{
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();

// always check if inertial nav has started and is ready
if (!ahrs.healthy()) {
check_failed(ARMING_CHECK_NONE, display_failure, "AHRS not healthy");
check_failed(ARMING_CHECK_NONE, true, "AHRS not healthy");
return false;
}

#ifndef ALLOW_ARM_NO_COMPASS
const Compass &_compass = AP::compass();
// check compass health
if (!_compass.healthy()) {
check_failed(ARMING_CHECK_NONE, display_failure, "Compass not healthy");
check_failed(ARMING_CHECK_NONE, true, "Compass not healthy");
return false;
}
#endif
Expand All @@ -462,19 +462,19 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method

// always check if the current mode allows arming
if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) {
check_failed(ARMING_CHECK_NONE, display_failure, "Mode not armable");
check_failed(ARMING_CHECK_NONE, true, "Mode not armable");
return false;
}

// always check motors
if (!motor_checks(display_failure)) {
if (!motor_checks(true)) {
return false;
}

// if we are using motor interlock switch and it's enabled, fail to arm
// skip check in Throw mode which takes control of the motor interlock
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
check_failed(ARMING_CHECK_NONE, display_failure, "Motor Interlock Enabled");
check_failed(ARMING_CHECK_NONE, true, "Motor Interlock Enabled");
return false;
}

Expand All @@ -496,7 +496,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
// check lean angle
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_INS)) {
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {
check_failed(ARMING_CHECK_INS, display_failure, "Leaning");
check_failed(ARMING_CHECK_INS, true, "Leaning");
return false;
}
}
Expand All @@ -505,7 +505,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
#if ADSB_ENABLED == ENABLE
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) {
if (copter.failsafe.adsb) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "ADSB threat detected");
check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected");
return false;
}
}
Expand All @@ -520,21 +520,21 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
#endif
// check throttle is not too low - must be above failsafe throttle
if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
check_failed(ARMING_CHECK_RC, display_failure, "%s below failsafe", rc_item);
check_failed(ARMING_CHECK_RC, true, "%s below failsafe", rc_item);
return false;
}

// check throttle is not too high - skips checks if arming from GCS in Guided
if (!(method == AP_Arming::Method::MAVLINK && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) {
// above top of deadband is too always high
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, display_failure, "%s too high", rc_item);
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
return false;
}
// in manual modes throttle must be at zero
#if FRAME_CONFIG != HELI_FRAME
if ((copter.flightmode->has_manual_throttle() || control_mode == DRIFT) && copter.channel_throttle->get_control_in() > 0) {
check_failed(ARMING_CHECK_RC, display_failure, "%s too high", rc_item);
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
return false;
}
#endif
Expand All @@ -543,7 +543,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method

// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
check_failed(ARMING_CHECK_NONE, display_failure, "Safety Switch");
check_failed(ARMING_CHECK_NONE, true, "Safety Switch");
return false;
}

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class AP_Arming_Copter : public AP_Arming
bool pre_arm_ekf_attitude_check();
bool pre_arm_terrain_check(bool display_failure);
bool pre_arm_proximity_check(bool display_failure);
bool arm_checks(bool display_failure, AP_Arming::Method method);
bool arm_checks(AP_Arming::Method method) override;

// NOTE! the following check functions *DO* call into AP_Arming:
bool ins_checks(bool display_failure) override;
Expand Down
14 changes: 14 additions & 0 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,20 @@ def configure_env(self, cfg, env):
'-Werror=inconsistent-missing-override',
'-Werror=overloaded-virtual',

# catch conversion issues:
'-Werror=bitfield-enum-conversion',
'-Werror=bool-conversion',
'-Werror=constant-conversion',
'-Werror=enum-conversion',
'-Werror=int-conversion',
'-Werror=literal-conversion',
'-Werror=non-literal-null-conversion',
'-Werror=null-conversion',
'-Werror=objc-literal-conversion',
# '-Werror=shorten-64-to-32', # ARRAY_SIZE() creates this all over the place as the caller typically takes a uint32_t not a size_t
'-Werror=string-conversion',
# '-Werror=sign-conversion', # can't use as we assign into AP_Int8 from uint8_ts

'-Wno-gnu-designator',
'-Wno-mismatched-tags',
'-Wno-gnu-variable-sized-type-not-at-end',
Expand Down
2 changes: 1 addition & 1 deletion libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class RC_Channel_PIDTest : public RC_Channel
class RC_Channels_PIDTest : public RC_Channels
{
public:
RC_Channel *channel(uint8_t chan) {
RC_Channel *channel(uint8_t chan) override {
return &obj_channels[chan];
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Dummy.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK
{
uint32_t telem_delay() const override { return 0; }
void handleMessage(mavlink_message_t * msg) override {}
bool try_send_message(enum ap_message id) { return true; }
bool try_send_message(enum ap_message id) override { return true; }
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override {}

Expand Down Expand Up @@ -52,7 +52,7 @@ class GCS_Dummy : public GCS
GCS_MAVLINK_Dummy &chan(const uint8_t ofs) override { return dummy_backend; }
const GCS_MAVLINK_Dummy &chan(const uint8_t ofs) const override { return dummy_backend; };

void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) { hal.console->printf("TOGCS: %s\n", text); }
void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) override { hal.console->printf("TOGCS: %s\n", text); }

MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
uint32_t custom_mode() const override { return 3; } // magic number
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/examples/routing/routing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class GCS_MAVLINK_routing : public GCS_MAVLINK

private:

void handleMessage(mavlink_message_t * msg) { }
void handleMessage(mavlink_message_t * msg) override { }
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return false ; }
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override { }
bool try_send_message(enum ap_message id) override { return false; }
Expand All @@ -54,7 +54,7 @@ class GCS_MAVLINK_routing : public GCS_MAVLINK


static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
static GCS_MAVLINK_routing gcs_link[MAVLINK_COMM_NUM_BUFFERS];
static GCS_MAVLINK_routing gcs_link[num_gcs];

extern mavlink_system_t mavlink_system;

Expand Down
2 changes: 1 addition & 1 deletion libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class RC_Channels_Example : public RC_Channels

protected:

int8_t flight_mode_channel_number() const { return 5; }
int8_t flight_mode_channel_number() const override { return 5; }

private:

Expand Down