mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 16:38:30 -04:00
Plane: if statement cleanup in QuadPlane::assign_tilt_to_fwd_thr
This commit is contained in:
parent
57cfe854b2
commit
16895003df
@ -2923,7 +2923,11 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
void QuadPlane::assign_tilt_to_fwd_thr(void) {
|
void QuadPlane::assign_tilt_to_fwd_thr(void) {
|
||||||
if (is_positive(q_fwd_thr_gain)) {
|
if (!is_positive(q_fwd_thr_gain)) {
|
||||||
|
q_fwd_throttle = 0.0f;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// Handle the case where we are limiting the forward pitch angle to prevent negative wing lift
|
// Handle the case where we are limiting the forward pitch angle to prevent negative wing lift
|
||||||
// and are using the forward thrust motor or tilting rotors to provide the forward acceleration
|
// and are using the forward thrust motor or tilting rotors to provide the forward acceleration
|
||||||
float fwd_tilt_rad = radians(constrain_float(-0.01f * (float)plane.nav_pitch_cd, 0.0f, 45.0f));
|
float fwd_tilt_rad = radians(constrain_float(-0.01f * (float)plane.nav_pitch_cd, 0.0f, 45.0f));
|
||||||
@ -2943,10 +2947,6 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
|
|||||||
q_fwd_throttle *= fwd_thr_scaler;
|
q_fwd_throttle *= fwd_thr_scaler;
|
||||||
q_fwd_nav_pitch_lim_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + 100.0f * q_fwd_pitch_lim * fwd_thr_scaler);
|
q_fwd_nav_pitch_lim_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + 100.0f * q_fwd_pitch_lim * fwd_thr_scaler);
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
|
||||||
q_fwd_throttle = 0.0f;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user