mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: Fix takeoff pitch for hand launch
This commit is contained in:
parent
39e1eb238d
commit
4e648734fa
@ -169,8 +169,8 @@ void Plane::takeoff_calc_pitch(void)
|
|||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (is_positive(g.takeoff_throttle_min_speed) || is_positive(g.takeoff_throttle_min_accel)) {
|
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
|
// Doing hand launch so need at least 5 deg pitch to prevent initial height loss
|
||||||
nav_pitch_cd = MIN(auto_state.takeoff_pitch_cd, 500);
|
nav_pitch_cd = MAX(auto_state.takeoff_pitch_cd, 500);
|
||||||
} else {
|
} else {
|
||||||
// Rise off ground takeoff so delay rotation until ground speed indicates adequate airspeed
|
// 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 = ((gps.ground_speed()*100) / (float)aparm.airspeed_cruise_cm) * auto_state.takeoff_pitch_cd;
|
||||||
|
Loading…
Reference in New Issue
Block a user