Plane: Remove meaningless semicolons

This commit is contained in:
murata 2022-02-05 21:21:31 +09:00 committed by Randy Mackay
parent 6c83f2262d
commit f8383df5a4
2 changed files with 2 additions and 2 deletions

View File

@ -127,7 +127,7 @@ bool ModeThermal::exit_heading_aligned() const
switch (plane.previous_mode->mode_number()) { switch (plane.previous_mode->mode_number()) {
case Mode::Number::AUTO: { case Mode::Number::AUTO: {
//Get the lat/lon of next Nav waypoint after this one: //Get the lat/lon of next Nav waypoint after this one:
AP_Mission::Mission_Command current_nav_cmd = plane.mission.get_current_nav_cmd();; AP_Mission::Mission_Command current_nav_cmd = plane.mission.get_current_nav_cmd();
return plane.mode_loiter.isHeadingLinedUp(plane.next_WP_loc, current_nav_cmd.content.location); return plane.mode_loiter.isHeadingLinedUp(plane.next_WP_loc, current_nav_cmd.content.location);
} }
case Mode::Number::FLY_BY_WIRE_B: case Mode::Number::FLY_BY_WIRE_B:

View File

@ -981,7 +981,7 @@ float QuadPlane::get_pilot_throttle()
float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f); float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f);
// this puts mid stick at hover throttle // this puts mid stick at hover throttle
return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);; return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);
} else { } else {
return throttle_in; return throttle_in;
} }