Plane: Adjust the grouping of functions to match the style

This commit is contained in:
muramura 2024-10-23 00:45:20 +09:00 committed by Peter Barker
parent e4ff0702ef
commit 7371e45dc0

View File

@ -2905,7 +2905,8 @@ QuadPlane::ActiveFwdThr QuadPlane::get_vfwd_method(void) const
/* /*
map from pitch tilt to fwd throttle when enabled map from pitch tilt to fwd throttle when enabled
*/ */
void QuadPlane::assign_tilt_to_fwd_thr(void) { void QuadPlane::assign_tilt_to_fwd_thr(void)
{
const auto fwd_thr_active = get_vfwd_method(); const auto fwd_thr_active = get_vfwd_method();
if (fwd_thr_active != ActiveFwdThr::NEW) { if (fwd_thr_active != ActiveFwdThr::NEW) {
@ -4201,7 +4202,7 @@ uint16_t QuadPlane::get_pilot_velocity_z_max_dn() const
{ {
if (is_zero(pilot_speed_z_max_dn)) { if (is_zero(pilot_speed_z_max_dn)) {
return abs(pilot_speed_z_max_up*100); return abs(pilot_speed_z_max_up*100);
} }
return abs(pilot_speed_z_max_dn*100); return abs(pilot_speed_z_max_dn*100);
} }
@ -4499,7 +4500,8 @@ void SLT_Transition::set_last_fw_pitch()
last_fw_nav_pitch_cd = plane.nav_pitch_cd; last_fw_nav_pitch_cd = plane.nav_pitch_cd;
} }
void SLT_Transition::force_transition_complete() { void SLT_Transition::force_transition_complete()
{
transition_state = TRANSITION_DONE; transition_state = TRANSITION_DONE;
in_forced_transition = false; in_forced_transition = false;
transition_start_ms = 0; transition_start_ms = 0;