forked from Archive/PX4-Autopilot
clang-tidy: enable readability-simplify-boolean-expr and fix
This commit is contained in:
parent
279df3b1b8
commit
967446af4c
|
@ -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,
|
||||
'
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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()
|
||||
|
|
|
@ -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());
|
||||
|
||||
|
|
|
@ -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 {
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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++;
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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");
|
||||
}
|
||||
// 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;
|
||||
}
|
||||
// set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_ABSPRESSURE, false, true, false, status);
|
||||
// failed = true;
|
||||
// }
|
||||
}
|
||||
|
||||
/* ---- IMU CONSISTENCY ---- */
|
||||
|
|
|
@ -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;
|
||||
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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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()) {
|
||||
|
|
|
@ -352,7 +352,7 @@ MissionFeasibilityChecker::checkTakeoff(const mission_s &mission, float home_alt
|
|||
return false;
|
||||
}
|
||||
|
||||
if (missionitem.nav_cmd != NAV_CMD_IDLE &&
|
||||
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 &&
|
||||
|
@ -374,13 +374,7 @@ MissionFeasibilityChecker::checkTakeoff(const mission_s &mission, float home_alt
|
|||
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;
|
||||
|
||||
}
|
||||
missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue