diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index fabb133097c5eaed91b9d216a20178e69f6e4ced..02d5b2def85db046a88fff12fcb525914facedc5 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -531,6 +531,9 @@ static struct { // should we use cross-tracking for this waypoint? bool no_crosstrack:1; + // in FBWA taildragger takeoff mode + bool fbwa_tdrag_takeoff_mode:1; + // Altitude threshold to complete a takeoff command in autonomous modes. Centimeters int32_t takeoff_altitude_cm; @@ -555,6 +558,7 @@ static struct { inverted_flight : false, next_wp_no_crosstrack : true, no_crosstrack : true, + fbwa_tdrag_takeoff_mode : false, takeoff_altitude_cm : 0, takeoff_pitch_cd : 0, highest_airspeed : 0, @@ -1309,6 +1313,16 @@ static void update_flight_mode(void) nav_pitch_cd = 0; channel_throttle->servo_out = 0; } + if (g.fbwa_tdrag_chan > 0) { + // check for the user enabling FBWA taildrag takeoff mode + bool tdrag_mode = (hal.rcin->read(g.fbwa_tdrag_chan-1) > 1700); + if (tdrag_mode && !auto_state.fbwa_tdrag_takeoff_mode) { + if (auto_state.highest_airspeed < g.takeoff_tdrag_speed1) { + auto_state.fbwa_tdrag_takeoff_mode = true; + gcs_send_text_P(SEVERITY_LOW, PSTR("FBWA tdrag mode\n")); + } + } + } break; } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 4ec57abd39e5b156d1321cd9ae5718f9128122a7..8cb5a7e6bbd54a33ad140915224497ee46102b7a 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -122,6 +122,7 @@ public: k_param_glide_slope_threshold, k_param_stab_pitch_down, k_param_terrain_lookahead, + k_param_fbwa_tdrag_chan, // 100: Arming parameters k_param_arming = 100, @@ -457,6 +458,7 @@ public: AP_Int16 terrain_lookahead; #endif AP_Int16 glide_slope_threshold; + AP_Int8 fbwa_tdrag_chan; // RC channels RC_Channel rc_1; diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 7158c7ce4f9786cf2a5fd69096c799110bf98108..5f14ce99f879f1ed49f505a35ce6062634af20e0 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -206,6 +206,12 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: User GSCALAR(takeoff_throttle_slewrate, "TKOFF_THR_SLEW", 0), + // @Param: FBWA_TDRAG_CHAN + // @DisplayName: FBWA taildragger channel + // @Description: This is a RC input channel which when it goes above 1700 enables FBWA taildragger takeoff mode. It should be assigned to a momentary switch. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA. Setting it to 0 disables this option. + // @User: Standard + GSCALAR(fbwa_tdrag_chan, "FBWA_TDRAG_CHAN", 0), + // @Param: LEVEL_ROLL_LIMIT // @DisplayName: Level flight roll limit // @Description: This controls the maximum bank angle in degrees during flight modes where level flight is desired, such as in the final stages of landing, and during auto takeoff. This should be a small angle (such as 5 degrees) to prevent a wing hitting the runway during takeoff or landing. Setting this to zero will completely disable heading hold on auto takeoff and final landing approach. diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 1e802f7578fb20bc191b78b7a1050df640b70af0..537faa230f2d2fc9f52c819ef2131dbd5e41989d 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -306,6 +306,13 @@ static void set_mode(enum FlightMode mode) autotune_restore(); } + // zero initial pitch and highest airspeed on mode change + auto_state.highest_airspeed = 0; + auto_state.initial_pitch_cd = ahrs.pitch_sensor; + + // disable taildrag takeoff on mode change + auto_state.fbwa_tdrag_takeoff_mode = false; + switch(control_mode) { case INITIALISING: @@ -351,8 +358,6 @@ static void set_mode(enum FlightMode mode) case AUTO: 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; diff --git a/ArduPlane/takeoff.pde b/ArduPlane/takeoff.pde index d588659ed6ca897f0f011a22aaa37d8473e7bc58..54f83951f2537837a7a20a92abbbfe8661c192d0 100644 --- a/ArduPlane/takeoff.pde +++ b/ArduPlane/takeoff.pde @@ -127,22 +127,28 @@ static void takeoff_calc_pitch(void) } /* - return a tail hold percentage during initial takeoff for a tail dragger + return a tail hold percentage during initial takeoff for a tail + dragger + + This can be used either in auto-takeoff or in FBWA mode with + FBWA_TDRAG_CHAN enabled */ static int8_t takeoff_tail_hold(void) { - if (control_mode != AUTO || auto_state.takeoff_complete) { + bool in_takeoff = ((control_mode == AUTO && !auto_state.takeoff_complete) || + (control_mode == FLY_BY_WIRE_A && auto_state.fbwa_tdrag_takeoff_mode)); + if (!in_takeoff) { // not in takeoff return 0; } if (g.takeoff_tdrag_elevator == 0) { // no takeoff elevator set - return 0; + goto return_zero; } if (auto_state.highest_airspeed >= g.takeoff_tdrag_speed1) { // we've passed speed1. We now raise the tail and aim for // level pitch. Return 0 meaning no fixed elevator setting - return 0; + goto return_zero; } if (ahrs.pitch_sensor > auto_state.initial_pitch_cd + 1000) { // the pitch has gone up by more then 10 degrees over the @@ -150,10 +156,17 @@ static int8_t takeoff_tail_hold(void) // early liftoff, perhaps due to a bad setting of // g.takeoff_tdrag_speed1. Go to level flight to prevent a // stall - return 0; + goto return_zero; } // we are holding the tail down return g.takeoff_tdrag_elevator; + +return_zero: + if (auto_state.fbwa_tdrag_takeoff_mode) { + gcs_send_text_P(SEVERITY_LOW, PSTR("FBWA tdrag off")); + auto_state.fbwa_tdrag_takeoff_mode = false; + } + return 0; } /*