From f5955d891541ae32d29b9a4d08f0275747685d62 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 18 Apr 2013 14:52:21 +0900 Subject: [PATCH] Copter: auto climb and descent params removed These params now reside in the AC_WPNav library --- ArduCopter/ArduCopter.pde | 2 +- ArduCopter/Attitude.pde | 2 +- ArduCopter/Parameters.h | 6 ++---- ArduCopter/Parameters.pde | 18 ------------------ 4 files changed, 4 insertions(+), 24 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 3ea2b98772..f3e2e3985d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1895,7 +1895,7 @@ void update_throttle_mode(void) case THROTTLE_AUTO: // auto pilot altitude controller with target altitude held in wp_nav.get_desired_alt() if(ap.auto_armed) { - get_throttle_althold_with_slew(wp_nav.get_desired_alt(), g.auto_velocity_z_min, g.auto_velocity_z_max); + get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity()); set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint } break; diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 7767d0d65f..77f37ea53f 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -1171,7 +1171,7 @@ get_throttle_land() { // if we are above 10m and the sonar does not sense anything perform regular alt hold descent if (current_loc.alt >= LAND_START_ALT && !(g.sonar_enabled && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) { - get_throttle_althold_with_slew(LAND_START_ALT, g.auto_velocity_z_min, -abs(g.land_speed)); + get_throttle_althold_with_slew(LAND_START_ALT, -wp_nav.get_descent_velocity(), -abs(g.land_speed)); }else{ get_throttle_rate_stabilized(-abs(g.land_speed)); diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index dc52defc8f..af3771c14a 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -215,8 +215,8 @@ public: k_param_circle_radius, k_param_waypoint_speed_max, // remove k_param_land_speed, - k_param_auto_velocity_z_min, - k_param_auto_velocity_z_max, // 219 + k_param_auto_velocity_z_min, // remove + k_param_auto_velocity_z_max, // remove - 219 // // 220: PI/D Controllers @@ -291,8 +291,6 @@ public: AP_Int16 circle_radius; AP_Int32 rtl_loiter_time; AP_Int16 land_speed; - AP_Int16 auto_velocity_z_min; // minimum vertical velocity (i.e. maximum descent) the autopilot may request - AP_Int16 auto_velocity_z_max; // maximum vertical velocity the autopilot may request AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 69162acbb5..729b311022 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -228,24 +228,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Standard GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED), - // @Param: AUTO_VELZ_MIN - // @DisplayName: Autopilot's min vertical speed (max descent) in cm/s - // @Description: The minimum vertical velocity (i.e. descent speed) the autopilot may request in cm/s - // @Units: Centimeters/Second - // @Range: -500 -50 - // @Increment: 10 - // @User: Standard - GSCALAR(auto_velocity_z_min, "AUTO_VELZ_MIN", AUTO_VELZ_MIN), - - // @Param: AUTO_VELZ_MAX - // @DisplayName: Auto pilot's max vertical speed in cm/s - // @Description: The maximum vertical velocity the autopilot may request in cm/s - // @Units: Centimeters/Second - // @Range: 50 500 - // @Increment: 10 - // @User: Standard - GSCALAR(auto_velocity_z_max, "AUTO_VELZ_MAX", AUTO_VELZ_MAX), - // @Param: PILOT_VELZ_MAX // @DisplayName: Pilot maximum vertical speed // @Description: The maximum vertical velocity the pilot may request in cm/s