From a4c675c23ed8bb61a1fea8ad490965654f85f9a0 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Wed, 30 Apr 2014 12:05:02 +0900 Subject: [PATCH] Copter: add PILOT_ACCEL_Z parameter Allows configurable z-axis acceleration when pilot is controlling altitude --- ArduCopter/Parameters.h | 5 +++-- ArduCopter/Parameters.pde | 11 ++++++++++- ArduCopter/config.h | 5 ++++- 3 files changed, 17 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 50d6ebd33..4c37ee7e4 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -110,7 +110,8 @@ public: k_param_rc_14, k_param_rally, k_param_hybrid_brake_rate, - k_param_hybrid_brake_angle_max, // 47 + k_param_hybrid_brake_angle_max, + k_param_pilot_accel_z, // 48 // 65: AP_Limits Library k_param_limits = 65, // deprecated - remove @@ -346,7 +347,7 @@ public: AP_Int32 rtl_loiter_time; AP_Int16 land_speed; AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request - + AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request // Throttle // diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 9667c4dd5..bc342e0c3 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -226,11 +226,20 @@ const AP_Param::Info var_info[] PROGMEM = { // @DisplayName: Pilot maximum vertical speed // @Description: The maximum vertical velocity the pilot may request in cm/s // @Units: Centimeters/Second - // @Range: 10 500 + // @Range: 50 500 // @Increment: 10 // @User: Standard GSCALAR(pilot_velocity_z_max, "PILOT_VELZ_MAX", PILOT_VELZ_MAX), + // @Param: PILOT_ACCEL_Z + // @DisplayName: Pilot vertical acceleration + // @Description: The vertical acceleration used when pilot is controlling the altitude + // @Units: cm/s/s + // @Range: 50 500 + // @Increment: 10 + // @User: Standard + GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT), + // @Param: THR_MIN // @DisplayName: Throttle Minimum // @Description: The minimum throttle that will be sent to the motors to keep them spinning diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 4ffc928b9..849925d80 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -676,10 +676,13 @@ # define THROTTLE_RATE_P 6.0f #endif -// default maximum vertical velocity the pilot may request +// default maximum vertical velocity and acceleration the pilot may request #ifndef PILOT_VELZ_MAX # define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s #endif +#ifndef PILOT_ACCEL_Z_DEFAULT + # define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control +#endif // max distance in cm above or below current location that will be used for the alt target when transitioning to alt-hold mode #ifndef ALT_HOLD_INIT_MAX_OVERSHOOT -- GitLab