mirror of https://github.com/ArduPilot/ardupilot
Plane: if statement cleanup in QuadPlane::assign_tilt_to_fwd_thr
This commit is contained in:
parent
57cfe854b2
commit
16895003df
|
@ -2923,29 +2923,29 @@ void QuadPlane::vtol_position_controller(void)
|
|||
}
|
||||
|
||||
void QuadPlane::assign_tilt_to_fwd_thr(void) {
|
||||
if (is_positive(q_fwd_thr_gain)) {
|
||||
// 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
|
||||
float fwd_tilt_rad = radians(constrain_float(-0.01f * (float)plane.nav_pitch_cd, 0.0f, 45.0f));
|
||||
q_fwd_nav_pitch_lim_cd = (int32_t)(-100.0f * q_fwd_pitch_lim);
|
||||
plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, q_fwd_nav_pitch_lim_cd);
|
||||
q_fwd_throttle = MIN(q_fwd_thr_gain * tanf(fwd_tilt_rad), 1.0f);
|
||||
|
||||
// To prevent forward motor prop strike, reduce throttle to zero when close to ground
|
||||
// When we are doing horizontal positioning in a VTOL land
|
||||
// we always allow the fwd motor to run. Otherwise a bad
|
||||
// lidar could cause the aircraft not to be able to
|
||||
// approach the landing point when landing below the takeoff point
|
||||
if (!in_vtol_land_approach()) {
|
||||
float alt_cutoff = MAX(0,vel_forward_alt_cutoff);
|
||||
float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||
float fwd_thr_scaler = linear_interpolate(0.0f, 1.0f, height_above_ground, alt_cutoff, alt_cutoff+2);
|
||||
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);
|
||||
}
|
||||
|
||||
} else {
|
||||
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
|
||||
// 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));
|
||||
q_fwd_nav_pitch_lim_cd = (int32_t)(-100.0f * q_fwd_pitch_lim);
|
||||
plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, q_fwd_nav_pitch_lim_cd);
|
||||
q_fwd_throttle = MIN(q_fwd_thr_gain * tanf(fwd_tilt_rad), 1.0f);
|
||||
|
||||
// To prevent forward motor prop strike, reduce throttle to zero when close to ground
|
||||
// When we are doing horizontal positioning in a VTOL land
|
||||
// we always allow the fwd motor to run. Otherwise a bad
|
||||
// lidar could cause the aircraft not to be able to
|
||||
// approach the landing point when landing below the takeoff point
|
||||
if (!in_vtol_land_approach()) {
|
||||
float alt_cutoff = MAX(0,vel_forward_alt_cutoff);
|
||||
float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||
float fwd_thr_scaler = linear_interpolate(0.0f, 1.0f, height_above_ground, alt_cutoff, alt_cutoff+2);
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue