mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: Don't lower nose when hand launching
This commit is contained in:
parent
d1d790019c
commit
82f68464d4
@ -168,8 +168,14 @@ void Plane::takeoff_calc_pitch(void)
|
||||
nav_pitch_cd = takeoff_pitch_min_cd;
|
||||
}
|
||||
} else {
|
||||
nav_pitch_cd = ((gps.ground_speed()*100) / (float)aparm.airspeed_cruise_cm) * auto_state.takeoff_pitch_cd;
|
||||
nav_pitch_cd = constrain_int32(nav_pitch_cd, 500, auto_state.takeoff_pitch_cd);
|
||||
if (is_positive(g.takeoff_throttle_min_speed) || is_positive(g.takeoff_throttle_min_accel)) {
|
||||
// Doing hand launch so don't lower pitch when low ground speed
|
||||
nav_pitch_cd = MIN(auto_state.takeoff_pitch_cd, 500);
|
||||
} else {
|
||||
// Rise off ground takeoff so delay rotation until ground speed indicates adequate airspeed
|
||||
nav_pitch_cd = ((gps.ground_speed()*100) / (float)aparm.airspeed_cruise_cm) * auto_state.takeoff_pitch_cd;
|
||||
nav_pitch_cd = constrain_int32(nav_pitch_cd, 500, auto_state.takeoff_pitch_cd);
|
||||
}
|
||||
}
|
||||
|
||||
if (aparm.stall_prevention != 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user