From b2a74951d15bad582cf2df5f84829cf8c312c00e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Sep 2012 11:43:17 +1000 Subject: [PATCH] APM: added RUDDER_STEER option when enabled, this uses only the rudder to steer during takeoff and landing, using aileron only for levelling --- ArduPlane/ArduPlane.pde | 13 +++++++++---- ArduPlane/Parameters.h | 2 ++ ArduPlane/Parameters.pde | 7 +++++++ 3 files changed, 18 insertions(+), 4 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 204235bca4..ad9bc1627f 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1076,7 +1076,7 @@ static void update_current_flight_mode(void) switch(nav_command_ID) { case MAV_CMD_NAV_TAKEOFF: - if (hold_course != -1) { + if (hold_course != -1 && g.rudder_steer == 0) { calc_nav_roll(); } else { nav_roll_cd = 0; @@ -1106,14 +1106,19 @@ static void update_current_flight_mode(void) break; case MAV_CMD_NAV_LAND: - calc_nav_roll(); + if (g.rudder_steer == 0) { + calc_nav_roll(); + } else { + nav_roll_cd = 0; + } - calc_nav_pitch(); - calc_throttle(); if (!alt_control_airspeed() || land_complete) { // hold pitch constant in final approach nav_pitch_cd = g.land_pitch_cd; + } else { + calc_nav_pitch(); } + calc_throttle(); if (land_complete) { // we are in the final stage of a landing - force diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 9a5d8c69f9..08bbfc5ada 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -74,6 +74,7 @@ public: k_param_land_flare_alt, k_param_land_flare_sec, k_param_crosstrack_min_distance, + k_param_rudder_steer, // 110: Telemetry control // @@ -331,6 +332,7 @@ public: AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger AP_Int8 sonar_enabled; AP_Int8 stick_mixing; + AP_Int8 rudder_steer; // Camera #if CAMERA == ENABLED diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index ce352826c6..42ca1e2e68 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -81,6 +81,13 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Advanced GSCALAR(stick_mixing, "STICK_MIXING", 1), + // @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 + // @Values: 0:Disabled,1:Enabled + // @User: User + GSCALAR(rudder_steer, "RUDDER_STEER", 0), + // @Param: land_pitch_cd // @DisplayName: Landing Pitch // @Description: Used in autoland for planes without airspeed sensors in hundredths of a degree