diff --git a/ArduCopter/commands_logic.cpp b/ArduCopter/commands_logic.cpp index 09d55bfa02..10b208c655 100644 --- a/ArduCopter/commands_logic.cpp +++ b/ArduCopter/commands_logic.cpp @@ -869,18 +869,15 @@ bool Copter::do_guided(const AP_Mission::Mission_Command& cmd) // set wp_nav's destination Location_Class dest(cmd.content.location); return guided_set_destination(dest); - break; } case MAV_CMD_CONDITION_YAW: do_yaw(cmd); return true; - break; default: // reject unrecognised command return false; - break; } return true; diff --git a/ArduCopter/control_auto.cpp b/ArduCopter/control_auto.cpp index df9bd88273..6c1252cd62 100644 --- a/ArduCopter/control_auto.cpp +++ b/ArduCopter/control_auto.cpp @@ -580,7 +580,6 @@ uint8_t Copter::get_default_auto_yaw_mode(bool rtl) case WP_YAW_BEHAVIOR_NONE: return AUTO_YAW_HOLD; - break; case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL: if (rtl) { @@ -588,16 +587,13 @@ uint8_t Copter::get_default_auto_yaw_mode(bool rtl) }else{ return AUTO_YAW_LOOK_AT_NEXT_WP; } - break; case WP_YAW_BEHAVIOR_LOOK_AHEAD: return AUTO_YAW_LOOK_AHEAD; - break; case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP: default: return AUTO_YAW_LOOK_AT_NEXT_WP; - break; } } @@ -717,29 +713,24 @@ float Copter::get_auto_heading(void) case AUTO_YAW_ROI: // point towards a location held in roi_WP return get_roi_yaw(); - break; case AUTO_YAW_LOOK_AT_HEADING: // keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed return yaw_look_at_heading; - break; case AUTO_YAW_LOOK_AHEAD: // Commanded Yaw to automatically look ahead. return get_look_ahead_yaw(); - break; case AUTO_YAW_RESETTOARMEDYAW: // changes yaw to be same as when quad was armed return initial_armed_bearing; - break; case AUTO_YAW_LOOK_AT_NEXT_WP: default: // point towards next waypoint. // we don't use wp_bearing because we don't want the copter to turn too much during flight return wp_nav.get_yaw(); - break; } } diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index dcb76ee6b6..5783e1869b 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -210,16 +210,13 @@ bool Copter::should_disarm_on_failsafe() { case ACRO: // if throttle is zero OR vehicle is landed disarm motors return ap.throttle_zero || ap.land_complete; - break; case AUTO: // if mission has not started AND vehicle is landed, disarm motors return !ap.auto_armed && ap.land_complete; - break; default: // used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold // if landed disarm return ap.land_complete; - break; } } diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index f71e991a52..8b23f21024 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -58,7 +58,6 @@ void Copter::motor_test_output() default: motor_test_stop(); return; - break; } // sanity check throttle values