From 90601c80e91e874f0f4183098b3ecabc19542336 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Thu, 28 Jun 2018 12:18:49 -0300 Subject: [PATCH] Sub: Simplify some returns MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- ArduSub/Attitude.cpp | 3 +-- ArduSub/commands.cpp | 7 +------ ArduSub/control_althold.cpp | 5 ++--- ArduSub/flight_mode.cpp | 9 +++++---- ArduSub/system.cpp | 9 ++++----- 5 files changed, 13 insertions(+), 20 deletions(-) diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index 828f57798c..a08d1f654d 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -199,7 +199,6 @@ uint16_t Sub::get_pilot_speed_dn() { if (g.pilot_speed_dn == 0) { return abs(g.pilot_speed_up); - } else { - return abs(g.pilot_speed_dn); } + return abs(g.pilot_speed_dn); } diff --git a/ArduSub/commands.cpp b/ArduSub/commands.cpp index 7eece9d7cc..17979cfba6 100644 --- a/ArduSub/commands.cpp +++ b/ArduSub/commands.cpp @@ -105,10 +105,5 @@ bool Sub::far_from_EKF_origin(const Location& loc) { // check distance to EKF origin const struct Location &ekf_origin = inertial_nav.get_origin(); - if (get_distance(ekf_origin, loc) > EKF_ORIGIN_MAX_DIST_M) { - return true; - } - - // close enough to origin - return false; + return (get_distance(ekf_origin, loc) > EKF_ORIGIN_MAX_DIST_M); } diff --git a/ArduSub/control_althold.cpp b/ArduSub/control_althold.cpp index db5b58bda2..2727be13ec 100644 --- a/ArduSub/control_althold.cpp +++ b/ArduSub/control_althold.cpp @@ -66,11 +66,10 @@ void Sub::althold_run() attitude_control.input_euler_angle_roll_pitch_yaw(target_roll * 1e2f, target_pitch * 1e2f, target_yaw * 1e2f, true); return; - - } else { - get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); } + get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); + // get pilot's desired yaw rate float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index 38f77783ae..89db87974b 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -194,10 +194,11 @@ bool Sub::mode_has_manual_throttle(control_mode_t mode) // arming_from_gcs should be set to true if the arming request comes from the ground station bool Sub::mode_allows_arming(control_mode_t mode, bool arming_from_gcs) { - if (mode_has_manual_throttle(mode) || mode == ALT_HOLD || mode == POSHOLD || (arming_from_gcs && mode == GUIDED)) { - return true; - } - return false; + return (mode_has_manual_throttle(mode) + || mode == ALT_HOLD + || mode == POSHOLD + || (arming_from_gcs&& mode == GUIDED) + ); } // notify_flight_mode - sets notify object based on flight mode. Only used for OreoLED notify device diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index cd868db73a..8b849acf34 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -259,10 +259,10 @@ bool Sub::ekf_position_ok() // if disarmed we accept a predicted horizontal position if (!motors.armed()) { return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs)); - } else { - // once armed we require a good absolute position and EKF must not be in const_pos_mode - return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode); } + + // once armed we require a good absolute position and EKF must not be in const_pos_mode + return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode); } // optflow_position_ok - returns true if optical flow based position estimate is ok @@ -282,9 +282,8 @@ bool Sub::optflow_position_ok() // if disarmed we accept a predicted horizontal relative position if (!motors.armed()) { return (filt_status.flags.pred_horiz_pos_rel); - } else { - return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode); } + return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode); #endif }