mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: prevent stalled takeoff with bad TKOFF_TDRAG_SPD1
go to level pitch if pitch rises by 10 degrees
This commit is contained in:
parent
d87619c2f1
commit
286479ee93
@ -530,12 +530,16 @@ static struct {
|
||||
// the highest airspeed we have reached since entering AUTO. Used
|
||||
// to control ground takeoff
|
||||
float highest_airspeed;
|
||||
|
||||
// initial pitch. Used to detect if nose is rising in a tail dragger
|
||||
int16_t initial_pitch_cd;
|
||||
} auto_state = {
|
||||
takeoff_complete : true,
|
||||
land_complete : false,
|
||||
takeoff_altitude_cm : 0,
|
||||
takeoff_pitch_cd : 0,
|
||||
highest_airspeed : 0
|
||||
highest_airspeed : 0,
|
||||
initial_pitch_cd : 0
|
||||
};
|
||||
|
||||
// true if we are in an auto-throttle mode, which means
|
||||
|
@ -337,6 +337,7 @@ static void set_mode(enum FlightMode mode)
|
||||
auto_throttle_mode = true;
|
||||
next_WP_loc = prev_WP_loc = current_loc;
|
||||
auto_state.highest_airspeed = 0;
|
||||
auto_state.initial_pitch_cd = ahrs.pitch_sensor;
|
||||
// start or resume the mission, based on MIS_AUTORESET
|
||||
mission.start_or_resume();
|
||||
break;
|
||||
|
@ -142,6 +142,14 @@ static int8_t takeoff_tail_hold(void)
|
||||
// level pitch. Return 0 meaning no fixed elevator setting
|
||||
return 0;
|
||||
}
|
||||
if (ahrs.pitch_sensor > auto_state.initial_pitch_cd + 1000) {
|
||||
// the pitch has gone up by more then 10 degrees over the
|
||||
// initial pitch. This may mean the nose is coming up for an
|
||||
// early liftoff, perhaps due to a bad setting of
|
||||
// g.takeoff_tdrag_speed1. Go to level flight to prevent a
|
||||
// stall
|
||||
return 0;
|
||||
}
|
||||
// we are holding the tail down
|
||||
return g.takeoff_tdrag_elevator;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user