Plane: added FLIGHT_OPTIONS bit for disabling pitch up check in takeoff

some takeoff procedures use high pitch angles
This commit is contained in:
Andrew Tridgell 2018-09-14 19:05:25 +10:00
parent a00e06ea13
commit 5ce418b4ea
3 changed files with 5 additions and 4 deletions

View File

@ -1173,7 +1173,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
// @Description: Flight mode specific options
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual Stabilize Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual, Stabilize, Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),

View File

@ -201,4 +201,5 @@ enum {
enum FlightOptions {
DIRECT_RUDDER_ONLY = (1 << 0),
CRUISE_TRIM_THROTTLE = (1 << 1),
DISABLE_TOFF_ATTITUDE_CHK = (1 << 2),
};

View File

@ -75,10 +75,10 @@ bool Plane::auto_takeoff_check(void)
goto no_launch;
}
if (!quadplane.is_tailsitter()) {
if (!quadplane.is_tailsitter() &&
!(g2.flight_options & FlightOptions::DISABLE_TOFF_ATTITUDE_CHK)) {
// Check aircraft attitude for bad launch
if (ahrs.pitch_sensor <= -3000 ||
ahrs.pitch_sensor >= 4500 ||
if (ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 ||
(!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Bad launch AUTO");
takeoff_state.accel_event_counter = 0;