mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
clang-tidy readability-simplify-boolean-expr
This commit is contained in:
@@ -54,12 +54,7 @@ TerrainEstimator::TerrainEstimator() :
|
||||
|
||||
bool TerrainEstimator::is_distance_valid(float distance)
|
||||
{
|
||||
if (distance > 40.0f || distance < 0.00001f) {
|
||||
return false;
|
||||
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
return (distance < 40.0f && distance > 0.00001f);
|
||||
}
|
||||
|
||||
void TerrainEstimator::predict(float dt, const struct vehicle_attitude_s *attitude,
|
||||
|
||||
@@ -351,12 +351,7 @@ bool is_safe(const struct safety_s *safety, const struct actuator_armed_s *armed
|
||||
// 3) Safety switch is present AND engaged -> actuators locked
|
||||
const bool lockdown = (armed->lockdown || armed->manual_lockdown);
|
||||
|
||||
if (!armed->armed || (armed->armed && lockdown) || (safety->safety_switch_available && !safety->safety_off)) {
|
||||
return true;
|
||||
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
return !armed->armed || (armed->armed && lockdown) || (safety->safety_switch_available && !safety->safety_off);
|
||||
}
|
||||
|
||||
transition_result_t
|
||||
|
||||
@@ -532,20 +532,16 @@ void Ekf2Replay::writeMessage(int &fd, void *data, size_t size)
|
||||
|
||||
bool Ekf2Replay::needToSaveMessage(uint8_t type)
|
||||
{
|
||||
if (type == LOG_ATT_MSG ||
|
||||
type == LOG_LPOS_MSG ||
|
||||
type == LOG_EST0_MSG ||
|
||||
type == LOG_EST1_MSG ||
|
||||
type == LOG_EST2_MSG ||
|
||||
type == LOG_EST3_MSG ||
|
||||
type == LOG_EST4_MSG ||
|
||||
type == LOG_EST5_MSG ||
|
||||
type == LOG_EST6_MSG ||
|
||||
type == LOG_CTS_MSG) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return !(type == LOG_ATT_MSG ||
|
||||
type == LOG_LPOS_MSG ||
|
||||
type == LOG_EST0_MSG ||
|
||||
type == LOG_EST1_MSG ||
|
||||
type == LOG_EST2_MSG ||
|
||||
type == LOG_EST3_MSG ||
|
||||
type == LOG_EST4_MSG ||
|
||||
type == LOG_EST5_MSG ||
|
||||
type == LOG_EST6_MSG ||
|
||||
type == LOG_CTS_MSG);
|
||||
}
|
||||
|
||||
// update all estimator topics and write them to log file
|
||||
|
||||
@@ -880,14 +880,7 @@ FixedwingAttitudeControl::task_main()
|
||||
_att_sp.fw_control_yaw = _att_sp.fw_control_yaw && _vcontrol_mode.flag_control_auto_enabled;
|
||||
|
||||
/* lock integrator until control is started */
|
||||
bool lock_integrator;
|
||||
|
||||
if (_vcontrol_mode.flag_control_rates_enabled && !_vehicle_status.is_rotary_wing) {
|
||||
lock_integrator = false;
|
||||
|
||||
} else {
|
||||
lock_integrator = true;
|
||||
}
|
||||
bool lock_integrator = !(_vcontrol_mode.flag_control_rates_enabled && !_vehicle_status.is_rotary_wing);
|
||||
|
||||
/* Simple handling of failsafe: deploy parachute if failsafe is on */
|
||||
if (_vcontrol_mode.flag_control_termination_enabled) {
|
||||
|
||||
@@ -1058,13 +1058,8 @@ FixedwingPositionControl::in_takeoff_situation()
|
||||
// in air for < 10s
|
||||
const hrt_abstime delta_takeoff = 10000000;
|
||||
|
||||
if (hrt_elapsed_time(&_time_went_in_air) < delta_takeoff
|
||||
&& _global_pos.alt <= _takeoff_ground_alt + _parameters.climbout_diff) {
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
return hrt_elapsed_time(&_time_went_in_air) < delta_takeoff
|
||||
&& _global_pos.alt <= _takeoff_ground_alt + _parameters.climbout_diff;
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -142,16 +142,10 @@ bool FixedwingLandDetector::_get_landed_state()
|
||||
_accel_horz_lp = _accel_horz_lp * 0.8f + _controlState.horz_acc_mag * 0.18f;
|
||||
|
||||
// crude land detector for fixedwing
|
||||
if (_velocity_xy_filtered < _params.maxVelocity
|
||||
&& _velocity_z_filtered < _params.maxClimbRate
|
||||
&& _airspeed_filtered < _params.maxAirSpeed
|
||||
&& _accel_horz_lp < _params.maxIntVelocity) {
|
||||
|
||||
landDetected = true;
|
||||
|
||||
} else {
|
||||
landDetected = false;
|
||||
}
|
||||
landDetected = _velocity_xy_filtered < _params.maxVelocity
|
||||
&& _velocity_z_filtered < _params.maxClimbRate
|
||||
&& _airspeed_filtered < _params.maxAirSpeed
|
||||
&& _accel_horz_lp < _params.maxIntVelocity;
|
||||
|
||||
} else {
|
||||
// Control state topic has timed out and we need to assume we're landed.
|
||||
|
||||
@@ -186,12 +186,7 @@ bool MulticopterLandDetector::_get_ground_contact_state()
|
||||
|
||||
// If pilots commands down or in auto mode and we are already below minimal thrust and we do not move down we assume ground contact
|
||||
// TODO: we need an accelerometer based check for vertical movement for flying without GPS
|
||||
if (manual_control_idle_or_auto && _has_minimal_thrust() &&
|
||||
(!verticalMovement || !_has_altitude_lock())) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
return manual_control_idle_or_auto && _has_minimal_thrust() && (!verticalMovement || !_has_altitude_lock());
|
||||
}
|
||||
|
||||
bool MulticopterLandDetector::_get_landed_state()
|
||||
@@ -231,14 +226,7 @@ bool MulticopterLandDetector::_get_landed_state()
|
||||
// if this persists for 8 seconds AND the drone is not
|
||||
// falling consider it to be landed. This should even sustain
|
||||
// quite acrobatic flight.
|
||||
if ((_min_trust_start > 0) &&
|
||||
(hrt_elapsed_time(&_min_trust_start) > 8000000)) {
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
return (_min_trust_start > 0) && (hrt_elapsed_time(&_min_trust_start) > 8000000);
|
||||
}
|
||||
|
||||
float armThresholdFactor = 1.0f;
|
||||
|
||||
@@ -563,11 +563,7 @@ bool BlockLocalPositionEstimator::landed()
|
||||
|
||||
bool disarmed_not_falling = (!_sub_armed.get().armed) && (!_sub_land.get().freefall);
|
||||
|
||||
if (!(_sub_land.get().landed || disarmed_not_falling)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return _sub_land.get().landed || disarmed_not_falling;
|
||||
}
|
||||
|
||||
void BlockLocalPositionEstimator::publishLocalPos()
|
||||
|
||||
@@ -948,7 +948,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
||||
mission_item->nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
mission_item->time_inside = mavlink_mission_item->param1;
|
||||
mission_item->loiter_radius = mavlink_mission_item->param3;
|
||||
mission_item->loiter_exit_xtrack = (mavlink_mission_item->param4 > 0) ? true : false;
|
||||
mission_item->loiter_exit_xtrack = (mavlink_mission_item->param4 > 0);
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_LAND:
|
||||
@@ -965,9 +965,9 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
||||
|
||||
case MAV_CMD_NAV_LOITER_TO_ALT:
|
||||
mission_item->nav_cmd = NAV_CMD_LOITER_TO_ALT;
|
||||
mission_item->force_heading = (mavlink_mission_item->param1 > 0) ? true : false;
|
||||
mission_item->force_heading = (mavlink_mission_item->param1 > 0);
|
||||
mission_item->loiter_radius = mavlink_mission_item->param2;
|
||||
mission_item->loiter_exit_xtrack = (mavlink_mission_item->param4 > 0) ? true : false;
|
||||
mission_item->loiter_exit_xtrack = (mavlink_mission_item->param4 > 0);
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_VTOL_TAKEOFF:
|
||||
|
||||
@@ -498,20 +498,14 @@ MissionBlock::get_time_inside(const struct mission_item_s &item)
|
||||
bool
|
||||
MissionBlock::item_contains_position(const struct mission_item_s *item)
|
||||
{
|
||||
if (item->nav_cmd == NAV_CMD_WAYPOINT ||
|
||||
item->nav_cmd == NAV_CMD_LOITER_UNLIMITED ||
|
||||
item->nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
|
||||
item->nav_cmd == NAV_CMD_LAND ||
|
||||
item->nav_cmd == NAV_CMD_TAKEOFF ||
|
||||
item->nav_cmd == NAV_CMD_LOITER_TO_ALT ||
|
||||
item->nav_cmd == NAV_CMD_VTOL_TAKEOFF ||
|
||||
item->nav_cmd == NAV_CMD_VTOL_LAND) {
|
||||
|
||||
return true;
|
||||
|
||||
}
|
||||
|
||||
return false;
|
||||
return item->nav_cmd == NAV_CMD_WAYPOINT ||
|
||||
item->nav_cmd == NAV_CMD_LOITER_UNLIMITED ||
|
||||
item->nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
|
||||
item->nav_cmd == NAV_CMD_LAND ||
|
||||
item->nav_cmd == NAV_CMD_TAKEOFF ||
|
||||
item->nav_cmd == NAV_CMD_LOITER_TO_ALT ||
|
||||
item->nav_cmd == NAV_CMD_VTOL_TAKEOFF ||
|
||||
item->nav_cmd == NAV_CMD_VTOL_LAND;
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -50,10 +50,5 @@ bool circuit_breaker_enabled(const char *breaker, int32_t magic)
|
||||
{
|
||||
int32_t val = -1;
|
||||
|
||||
if (PX4_PARAM_GET_BYNAME(breaker, &val) == 0 && val == magic) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
return (PX4_PARAM_GET_BYNAME(breaker, &val) == 0) && (val == magic);
|
||||
}
|
||||
|
||||
|
||||
@@ -662,7 +662,7 @@ void VtolAttitudeControl::task_main()
|
||||
parameters_update(); // initialize parameter cache
|
||||
|
||||
/* update vtol vehicle status*/
|
||||
_vtol_vehicle_status.fw_permanent_stab = _params.vtol_fw_permanent_stab == 1 ? true : false;
|
||||
_vtol_vehicle_status.fw_permanent_stab = (_params.vtol_fw_permanent_stab == 1);
|
||||
|
||||
// make sure we start with idle in mc mode
|
||||
_vtol_type->set_idle_mc();
|
||||
@@ -714,7 +714,7 @@ void VtolAttitudeControl::task_main()
|
||||
parameters_update();
|
||||
}
|
||||
|
||||
_vtol_vehicle_status.fw_permanent_stab = _params.vtol_fw_permanent_stab == 1 ? true : false;
|
||||
_vtol_vehicle_status.fw_permanent_stab = (_params.vtol_fw_permanent_stab == 1);
|
||||
|
||||
mc_virtual_att_sp_poll();
|
||||
fw_virtual_att_sp_poll();
|
||||
|
||||
Reference in New Issue
Block a user