From 9697ff5d6dbb0f19e133fc40865d2d8abacfdb4a Mon Sep 17 00:00:00 2001 From: Michael Warren Date: Sat, 9 Feb 2013 21:40:16 +1000 Subject: [PATCH] Plane: Added extra parameter to specify at what speed in auto-takeoff throttle should engage This adds TKOFF_THR_MINSPD in m/s --- ArduPlane/Attitude.pde | 8 ++++++-- ArduPlane/Parameters.h | 2 ++ ArduPlane/Parameters.pde | 9 +++++++++ 3 files changed, 17 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index b5422702fc..ff6cd2b09e 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -387,7 +387,7 @@ static void throttle_slew_limit(int16_t last_throttle) * AND * 2 - Our reported altitude is within 10 meters of the home altitude. * 3 - Our reported speed is under 5 meters per second. - * 4 - We are not performing a takeoff in Auto mode + * 4 - We are not performing a takeoff in Auto mode or takeoff speed not yet reached * OR * 5 - Home location is not set */ @@ -403,7 +403,11 @@ static bool suppress_throttle(void) return false; } - if (control_mode==AUTO && takeoff_complete == false) { + if (control_mode==AUTO && + takeoff_complete == false && + g_gps != NULL && + g_gps->status() == GPS::GPS_OK && + g_gps->ground_speed >= g.takeoff_throttle_min_speed*100) { // we're in auto takeoff throttle_suppressed = false; return false; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 2173cffbaf..ac25682c57 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -78,6 +78,7 @@ public: k_param_throttle_nudge, k_param_alt_offset, k_param_ins, // libraries/AP_InertialSensor variables + k_param_takeoff_throttle_min_speed, // 110: Telemetry control // @@ -354,6 +355,7 @@ public: AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger AP_Int8 stick_mixing; AP_Int8 rudder_steer; + AP_Float takeoff_throttle_min_speed; // RC channels RC_Channel channel_roll; diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 7333a95b39..4f646c2f74 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -88,6 +88,15 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Advanced GSCALAR(stick_mixing, "STICK_MIXING", 1), + // @Param: TKOFF_THR_MINSPD + // @DisplayName: Takeoff throttle min speed + // @Description: Minimum GPS ground speed in m/s before un-suppressing throttle in auto-takeoff. This is meant to be used for catapult launches where you want the motor to engage only after the plane leaves the catapult. Note that the GPS velocity will lag the real velocity by about 0.5seconds. + // @Units: m/s + // @Range: 0 30 + // @Increment: 0.1 + // @User: User + GSCALAR(takeoff_throttle_min_speed, "TKOFF_THR_MINSPD", 0), + // @Param: RUDDER_STEER // @DisplayName: Rudder steering on takeoff and landing // @Description: When enabled, only rudder will be used for steering during takeoff and landing, with the ailerons used to hold the plane level