From 967446af4c5c259bccb280c3f6faba7372957484 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 27 Oct 2019 18:18:31 -0400 Subject: [PATCH] clang-tidy: enable readability-simplify-boolean-expr and fix --- .clang-tidy | 1 - platforms/posix/src/px4/common/main.cpp | 6 +-- .../FlightTasks/tasks/Auto/FlightTaskAuto.cpp | 18 ++----- .../tasks/Utility/ObstacleAvoidance.cpp | 2 +- src/lib/hysteresis/hysteresis.cpp | 2 +- src/lib/parameters/parameters.cpp | 2 +- src/lib/rc/dsm.cpp | 2 +- .../terrain_estimation/terrain_estimator.cpp | 2 +- src/modules/commander/Commander.cpp | 6 +-- src/modules/commander/PreflightCheck.cpp | 20 +++---- .../land_detector/MulticopterLandDetector.cpp | 23 ++------ .../land_detector/RoverLandDetector.cpp | 6 +-- src/modules/navigator/follow_target.cpp | 4 +- .../navigator/mission_feasibility_checker.cpp | 52 ++++++++----------- src/modules/vtol_att_control/standard.cpp | 2 +- 15 files changed, 54 insertions(+), 94 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 7ae7ddeba5..b887b9ecd9 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -99,7 +99,6 @@ Checks: '*, -readability-redundant-control-flow, -readability-redundant-declaration, -readability-redundant-member-init, - -readability-simplify-boolean-expr, -readability-static-accessed-through-instance, -readability-static-definition-in-anonymous-namespace, ' diff --git a/platforms/posix/src/px4/common/main.cpp b/platforms/posix/src/px4/common/main.cpp index e139550b27..16db26ab86 100644 --- a/platforms/posix/src/px4/common/main.cpp +++ b/platforms/posix/src/px4/common/main.cpp @@ -590,11 +590,7 @@ bool is_already_running(int instance) if (fcntl(fd, F_SETLK, &fl) == -1) { // We failed to create a file lock, must be already locked. - if (errno == EACCES || errno == EAGAIN) { - return true; - } - - return false; + return errno == EACCES || errno == EAGAIN; } errno = 0; diff --git a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp index 1bd524020a..d53d0bbb57 100644 --- a/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp +++ b/src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp @@ -354,8 +354,8 @@ bool FlightTaskAuto::_evaluateGlobalReference() return true; } - double ref_lat = _sub_vehicle_local_position.get().ref_lat; - double ref_lon = _sub_vehicle_local_position.get().ref_lon; + double ref_lat = _sub_vehicle_local_position.get().ref_lat; + double ref_lon = _sub_vehicle_local_position.get().ref_lon; _reference_altitude = _sub_vehicle_local_position.get().ref_alt; if (!_sub_vehicle_local_position.get().z_global) { @@ -372,20 +372,10 @@ bool FlightTaskAuto::_evaluateGlobalReference() } // init projection - map_projection_init(&_reference_position, - ref_lat, - ref_lon); + map_projection_init(&_reference_position, ref_lat, ref_lon); // check if everything is still finite - if (PX4_ISFINITE(_reference_altitude) - && PX4_ISFINITE(_sub_vehicle_local_position.get().ref_lat) - && PX4_ISFINITE(_sub_vehicle_local_position.get().ref_lon)) { - return true; - - } else { - // no valid reference - return false; - } + return PX4_ISFINITE(_reference_altitude) && PX4_ISFINITE(ref_lat) && PX4_ISFINITE(ref_lon); } void FlightTaskAuto::_setDefaultConstraints() diff --git a/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.cpp b/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.cpp index a4677e8222..92a6a40959 100644 --- a/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.cpp +++ b/src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.cpp @@ -70,7 +70,7 @@ void ObstacleAvoidance::injectAvoidanceSetpoints(Vector3f &pos_sp, Vector3f &vel const bool avoidance_data_timeout = hrt_elapsed_time((hrt_abstime *)&_sub_vehicle_trajectory_waypoint.get().timestamp) > TRAJECTORY_STREAM_TIMEOUT_US; const bool avoidance_point_valid = - _sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid == true; + _sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid; _avoidance_point_not_valid_hysteresis.set_state_and_update(!avoidance_point_valid, hrt_absolute_time()); diff --git a/src/lib/hysteresis/hysteresis.cpp b/src/lib/hysteresis/hysteresis.cpp index e75327de8a..07f14e4b2e 100644 --- a/src/lib/hysteresis/hysteresis.cpp +++ b/src/lib/hysteresis/hysteresis.cpp @@ -45,7 +45,7 @@ namespace systemlib void Hysteresis::set_hysteresis_time_from(const bool from_state, const hrt_abstime new_hysteresis_time_us) { - if (from_state == true) { + if (from_state) { _time_from_true_us = new_hysteresis_time_us; } else { diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index 1be858bf2c..70cbef8ce7 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -501,7 +501,7 @@ param_value_is_default(param_t param) param_lock_reader(); s = param_find_changed(param); param_unlock_reader(); - return s ? false : true; + return s == nullptr; } bool diff --git a/src/lib/rc/dsm.cpp b/src/lib/rc/dsm.cpp index 765bbdaaef..fe9f380f84 100644 --- a/src/lib/rc/dsm.cpp +++ b/src/lib/rc/dsm.cpp @@ -712,7 +712,7 @@ dsm_parse(const uint64_t now, const uint8_t *frame, const unsigned len, uint16_t dsm_partial_frame_count = 0; /* if decoding failed, set proto to desync */ - if (decode_ret == false) { + if (!decode_ret) { dsm_decode_state = DSM_DECODE_STATE_DESYNC; dsm_frame_drops++; } diff --git a/src/lib/terrain_estimation/terrain_estimator.cpp b/src/lib/terrain_estimation/terrain_estimator.cpp index ed1f46bde5..9f376bccf1 100644 --- a/src/lib/terrain_estimation/terrain_estimator.cpp +++ b/src/lib/terrain_estimation/terrain_estimator.cpp @@ -186,7 +186,7 @@ void TerrainEstimator::measurement_update(uint64_t time_ref, const struct vehicl } if (reinit) { - memset(&_x._data[0], 0, sizeof(_x._data)); + _x.zero(); _P.setZero(); _P(0, 0) = _P(1, 1) = _P(2, 2) = 0.1f; } diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 3d8aa5df6c..c168f13a93 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1983,16 +1983,14 @@ Commander::run() /* handle the case where RC signal was regained */ if (!status_flags.rc_signal_found_once) { status_flags.rc_signal_found_once = true; - set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_RCRECEIVER, true, true, true - && status_flags.rc_calibration_valid, status); + set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_RCRECEIVER, true, true, status_flags.rc_calibration_valid, status); status_changed = true; } else { if (status.rc_signal_lost) { mavlink_log_info(&mavlink_log_pub, "Manual control regained after %llums", hrt_elapsed_time(&rc_signal_lost_timestamp) / 1000); - set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_RCRECEIVER, true, true, true - && status_flags.rc_calibration_valid, status); + set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_RCRECEIVER, true, true, status_flags.rc_calibration_valid, status); status_changed = true; } } diff --git a/src/modules/commander/PreflightCheck.cpp b/src/modules/commander/PreflightCheck.cpp index a4c61b5b30..9e92bafe24 100644 --- a/src/modules/commander/PreflightCheck.cpp +++ b/src/modules/commander/PreflightCheck.cpp @@ -868,7 +868,7 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, veh /* ---- BARO ---- */ if (checkSensors) { - bool prime_found = false; + //bool prime_found = false; int32_t prime_id = -1; param_get(param_find("CAL_BARO_PRIME"), &prime_id); @@ -887,7 +887,7 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, veh if (baroCheck(mavlink_log_pub, status, i, !required, device_id, report_fail)) { if ((prime_id > 0) && (device_id == prime_id)) { - prime_found = true; + //prime_found = true; } } else { @@ -900,14 +900,14 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, veh // TODO there is no logic in place to calibrate the primary baro yet // // check if the primary device is present - if (!prime_found && false) { - if (reportFailures && !failed) { - mavlink_log_critical(mavlink_log_pub, "Primary barometer not operational"); - } - - set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_ABSPRESSURE, false, true, false, status); - failed = true; - } + // if (false) { + // if (reportFailures && !failed) { + // mavlink_log_critical(mavlink_log_pub, "Primary barometer not operational"); + // } + + // set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_ABSPRESSURE, false, true, false, status); + // failed = true; + // } } /* ---- IMU CONSISTENCY ---- */ diff --git a/src/modules/land_detector/MulticopterLandDetector.cpp b/src/modules/land_detector/MulticopterLandDetector.cpp index 5eaf2f0fff..96a78c3fd8 100644 --- a/src/modules/land_detector/MulticopterLandDetector.cpp +++ b/src/modules/land_detector/MulticopterLandDetector.cpp @@ -165,12 +165,8 @@ bool MulticopterLandDetector::_get_ground_contact_state() bool hit_ground = _in_descend && !vertical_movement; // TODO: we need an accelerometer based check for vertical movement for flying without GPS - if ((_has_low_thrust() || hit_ground) && (!_horizontal_movement || !_has_position_lock()) - && (!vertical_movement || !_has_altitude_lock())) { - return true; - } - - return false; + return (_has_low_thrust() || hit_ground) && (!_horizontal_movement || !_has_position_lock()) + && (!vertical_movement || !_has_altitude_lock()); } bool MulticopterLandDetector::_get_maybe_landed_state() @@ -215,12 +211,8 @@ bool MulticopterLandDetector::_get_maybe_landed_state() return (_min_trust_start > 0) && (hrt_elapsed_time(&_min_trust_start) > 8_s); } - if (_ground_contact_hysteresis.get_state() && _has_minimal_thrust() && !rotating) { - // Ground contact, no thrust and no movement -> landed - return true; - } - - return false; + // Ground contact, no thrust and no movement -> landed + return _ground_contact_hysteresis.get_state() && _has_minimal_thrust() && !rotating; } bool MulticopterLandDetector::_get_landed_state() @@ -318,12 +310,7 @@ bool MulticopterLandDetector::_has_minimal_thrust() bool MulticopterLandDetector::_get_ground_effect_state() { - if (_in_descend && !_horizontal_movement) { - return true; - - } else { - return false; - } + return _in_descend && !_horizontal_movement; } } // namespace land_detector diff --git a/src/modules/land_detector/RoverLandDetector.cpp b/src/modules/land_detector/RoverLandDetector.cpp index 5a69f537aa..7ac174f0ff 100644 --- a/src/modules/land_detector/RoverLandDetector.cpp +++ b/src/modules/land_detector/RoverLandDetector.cpp @@ -51,11 +51,7 @@ bool RoverLandDetector::_get_ground_contact_state() bool RoverLandDetector::_get_landed_state() { - if (!_actuator_armed.armed) { - return true; - } - - return false; + return !_actuator_armed.armed; } } // namespace land_detector diff --git a/src/modules/navigator/follow_target.cpp b/src/modules/navigator/follow_target.cpp index 629161a84b..81cb783fd7 100644 --- a/src/modules/navigator/follow_target.cpp +++ b/src/modules/navigator/follow_target.cpp @@ -240,7 +240,7 @@ void FollowTarget::on_active() case TRACK_POSITION: { - if (_radius_entered == true) { + if (_radius_entered) { _follow_target_state = TRACK_VELOCITY; } else if (target_velocity_valid()) { @@ -259,7 +259,7 @@ void FollowTarget::on_active() case TRACK_VELOCITY: { - if (_radius_exited == true) { + if (_radius_exited) { _follow_target_state = TRACK_POSITION; } else if (target_velocity_valid()) { diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index 456db59fa9..86ddef9baa 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -352,35 +352,29 @@ MissionFeasibilityChecker::checkTakeoff(const mission_s &mission, float home_alt return false; } - if (missionitem.nav_cmd != NAV_CMD_IDLE && - missionitem.nav_cmd != NAV_CMD_DELAY && - missionitem.nav_cmd != NAV_CMD_DO_JUMP && - missionitem.nav_cmd != NAV_CMD_DO_CHANGE_SPEED && - missionitem.nav_cmd != NAV_CMD_DO_SET_HOME && - missionitem.nav_cmd != NAV_CMD_DO_SET_SERVO && - missionitem.nav_cmd != NAV_CMD_DO_LAND_START && - missionitem.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL && - missionitem.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL && - missionitem.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE && - missionitem.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE && - missionitem.nav_cmd != NAV_CMD_VIDEO_START_CAPTURE && - missionitem.nav_cmd != NAV_CMD_VIDEO_STOP_CAPTURE && - missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONFIGURE && - missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONTROL && - missionitem.nav_cmd != NAV_CMD_DO_SET_ROI && - missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_LOCATION && - missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_WPNEXT_OFFSET && - missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_NONE && - missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST && - missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL && - missionitem.nav_cmd != NAV_CMD_SET_CAMERA_MODE && - missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION) { - takeoff_first = false; - - } else { - takeoff_first = true; - - } + takeoff_first = !(missionitem.nav_cmd != NAV_CMD_IDLE && + missionitem.nav_cmd != NAV_CMD_DELAY && + missionitem.nav_cmd != NAV_CMD_DO_JUMP && + missionitem.nav_cmd != NAV_CMD_DO_CHANGE_SPEED && + missionitem.nav_cmd != NAV_CMD_DO_SET_HOME && + missionitem.nav_cmd != NAV_CMD_DO_SET_SERVO && + missionitem.nav_cmd != NAV_CMD_DO_LAND_START && + missionitem.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL && + missionitem.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL && + missionitem.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE && + missionitem.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE && + missionitem.nav_cmd != NAV_CMD_VIDEO_START_CAPTURE && + missionitem.nav_cmd != NAV_CMD_VIDEO_STOP_CAPTURE && + missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONFIGURE && + missionitem.nav_cmd != NAV_CMD_DO_MOUNT_CONTROL && + missionitem.nav_cmd != NAV_CMD_DO_SET_ROI && + missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_LOCATION && + missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_WPNEXT_OFFSET && + missionitem.nav_cmd != NAV_CMD_DO_SET_ROI_NONE && + missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST && + missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL && + missionitem.nav_cmd != NAV_CMD_SET_CAMERA_MODE && + missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION); } } diff --git a/src/modules/vtol_att_control/standard.cpp b/src/modules/vtol_att_control/standard.cpp index 8bcf9a0c5f..85145676e8 100644 --- a/src/modules/vtol_att_control/standard.cpp +++ b/src/modules/vtol_att_control/standard.cpp @@ -127,7 +127,7 @@ void Standard::update_vtol_state() } else if (_vtol_schedule.flight_mode == vtol_mode::FW_MODE) { // transition to mc mode - if (_vtol_vehicle_status->vtol_transition_failsafe == true) { + if (_vtol_vehicle_status->vtol_transition_failsafe) { // Failsafe event, engage mc motors immediately _vtol_schedule.flight_mode = vtol_mode::MC_MODE; _pusher_throttle = 0.0f;