Copter: To remove a break after the return statement.

This commit is contained in:
murata 2016-10-08 15:39:24 +09:00 committed by Lucas De Marchi
parent 2b144d5c3d
commit 57c61ace62
4 changed files with 0 additions and 16 deletions

View File

@ -869,18 +869,15 @@ bool Copter::do_guided(const AP_Mission::Mission_Command& cmd)
// set wp_nav's destination // set wp_nav's destination
Location_Class dest(cmd.content.location); Location_Class dest(cmd.content.location);
return guided_set_destination(dest); return guided_set_destination(dest);
break;
} }
case MAV_CMD_CONDITION_YAW: case MAV_CMD_CONDITION_YAW:
do_yaw(cmd); do_yaw(cmd);
return true; return true;
break;
default: default:
// reject unrecognised command // reject unrecognised command
return false; return false;
break;
} }
return true; return true;

View File

@ -580,7 +580,6 @@ uint8_t Copter::get_default_auto_yaw_mode(bool rtl)
case WP_YAW_BEHAVIOR_NONE: case WP_YAW_BEHAVIOR_NONE:
return AUTO_YAW_HOLD; return AUTO_YAW_HOLD;
break;
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL: case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL:
if (rtl) { if (rtl) {
@ -588,16 +587,13 @@ uint8_t Copter::get_default_auto_yaw_mode(bool rtl)
}else{ }else{
return AUTO_YAW_LOOK_AT_NEXT_WP; return AUTO_YAW_LOOK_AT_NEXT_WP;
} }
break;
case WP_YAW_BEHAVIOR_LOOK_AHEAD: case WP_YAW_BEHAVIOR_LOOK_AHEAD:
return AUTO_YAW_LOOK_AHEAD; return AUTO_YAW_LOOK_AHEAD;
break;
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP: case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP:
default: default:
return AUTO_YAW_LOOK_AT_NEXT_WP; return AUTO_YAW_LOOK_AT_NEXT_WP;
break;
} }
} }
@ -717,29 +713,24 @@ float Copter::get_auto_heading(void)
case AUTO_YAW_ROI: case AUTO_YAW_ROI:
// point towards a location held in roi_WP // point towards a location held in roi_WP
return get_roi_yaw(); return get_roi_yaw();
break;
case AUTO_YAW_LOOK_AT_HEADING: case AUTO_YAW_LOOK_AT_HEADING:
// keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed // keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed
return yaw_look_at_heading; return yaw_look_at_heading;
break;
case AUTO_YAW_LOOK_AHEAD: case AUTO_YAW_LOOK_AHEAD:
// Commanded Yaw to automatically look ahead. // Commanded Yaw to automatically look ahead.
return get_look_ahead_yaw(); return get_look_ahead_yaw();
break;
case AUTO_YAW_RESETTOARMEDYAW: case AUTO_YAW_RESETTOARMEDYAW:
// changes yaw to be same as when quad was armed // changes yaw to be same as when quad was armed
return initial_armed_bearing; return initial_armed_bearing;
break;
case AUTO_YAW_LOOK_AT_NEXT_WP: case AUTO_YAW_LOOK_AT_NEXT_WP:
default: default:
// point towards next waypoint. // point towards next waypoint.
// we don't use wp_bearing because we don't want the copter to turn too much during flight // we don't use wp_bearing because we don't want the copter to turn too much during flight
return wp_nav.get_yaw(); return wp_nav.get_yaw();
break;
} }
} }

View File

@ -210,16 +210,13 @@ bool Copter::should_disarm_on_failsafe() {
case ACRO: case ACRO:
// if throttle is zero OR vehicle is landed disarm motors // if throttle is zero OR vehicle is landed disarm motors
return ap.throttle_zero || ap.land_complete; return ap.throttle_zero || ap.land_complete;
break;
case AUTO: case AUTO:
// if mission has not started AND vehicle is landed, disarm motors // if mission has not started AND vehicle is landed, disarm motors
return !ap.auto_armed && ap.land_complete; return !ap.auto_armed && ap.land_complete;
break;
default: default:
// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold // used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold
// if landed disarm // if landed disarm
return ap.land_complete; return ap.land_complete;
break;
} }
} }

View File

@ -58,7 +58,6 @@ void Copter::motor_test_output()
default: default:
motor_test_stop(); motor_test_stop();
return; return;
break;
} }
// sanity check throttle values // sanity check throttle values