mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
Plane: Adjust the grouping of functions to match the style
This commit is contained in:
parent
e4ff0702ef
commit
7371e45dc0
@ -2905,7 +2905,8 @@ QuadPlane::ActiveFwdThr QuadPlane::get_vfwd_method(void) const
|
||||
/*
|
||||
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();
|
||||
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)) {
|
||||
return abs(pilot_speed_z_max_up*100);
|
||||
}
|
||||
}
|
||||
return abs(pilot_speed_z_max_dn*100);
|
||||
}
|
||||
|
||||
@ -4499,8 +4500,9 @@ void SLT_Transition::set_last_fw_pitch()
|
||||
last_fw_nav_pitch_cd = plane.nav_pitch_cd;
|
||||
}
|
||||
|
||||
void SLT_Transition::force_transition_complete() {
|
||||
transition_state = TRANSITION_DONE;
|
||||
void SLT_Transition::force_transition_complete()
|
||||
{
|
||||
transition_state = TRANSITION_DONE;
|
||||
in_forced_transition = false;
|
||||
transition_start_ms = 0;
|
||||
transition_low_airspeed_ms = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user