mirror of https://github.com/ArduPilot/ardupilot
Copter: Remove parameter RNGFND_GAIN
This commit is contained in:
parent
3e65570b36
commit
fed422e802
|
@ -167,16 +167,6 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),
|
GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
|
||||||
// @Param: RNGFND_GAIN
|
|
||||||
// @DisplayName: Rangefinder gain
|
|
||||||
// @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter
|
|
||||||
// @Range: 0.01 2.0
|
|
||||||
// @Increment: 0.01
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(rangefinder_gain, "RNGFND_GAIN", RANGEFINDER_GAIN_DEFAULT),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Param: FS_GCS_ENABLE
|
// @Param: FS_GCS_ENABLE
|
||||||
// @DisplayName: Ground Station Failsafe Enable
|
// @DisplayName: Ground Station Failsafe Enable
|
||||||
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
|
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
|
||||||
|
@ -346,7 +336,7 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
// @DisplayName: Channel 6 Tuning
|
// @DisplayName: Channel 6 Tuning
|
||||||
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
|
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,41:RangeFinder Gain,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,58:SysID Magnitude
|
// @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,58:SysID Magnitude
|
||||||
GSCALAR(radio_tuning, "TUNE", 0),
|
GSCALAR(radio_tuning, "TUNE", 0),
|
||||||
|
|
||||||
// @Param: FRAME_TYPE
|
// @Param: FRAME_TYPE
|
||||||
|
|
|
@ -102,7 +102,7 @@ public:
|
||||||
k_param_acro_trainer,
|
k_param_acro_trainer,
|
||||||
k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max
|
k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max
|
||||||
k_param_circle_rate, // deprecated - remove
|
k_param_circle_rate, // deprecated - remove
|
||||||
k_param_rangefinder_gain,
|
k_param_rangefinder_gain, // deprecated - remove
|
||||||
k_param_ch8_option_old, // deprecated
|
k_param_ch8_option_old, // deprecated
|
||||||
k_param_arming_check_old, // deprecated - remove
|
k_param_arming_check_old, // deprecated - remove
|
||||||
k_param_sprayer,
|
k_param_sprayer,
|
||||||
|
@ -403,10 +403,6 @@ public:
|
||||||
AP_Int8 rtl_alt_type;
|
AP_Int8 rtl_alt_type;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
|
||||||
AP_Float rangefinder_gain;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
AP_Int8 failsafe_gcs; // ground station failsafe behavior
|
AP_Int8 failsafe_gcs; // ground station failsafe behavior
|
||||||
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
||||||
|
|
||||||
|
|
|
@ -81,10 +81,6 @@
|
||||||
# define RANGEFINDER_TIMEOUT_MS 1000 // rangefinder filter reset if no updates from sensor in 1 second
|
# define RANGEFINDER_TIMEOUT_MS 1000 // rangefinder filter reset if no updates from sensor in 1 second
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RANGEFINDER_GAIN_DEFAULT
|
|
||||||
# define RANGEFINDER_GAIN_DEFAULT 0.8f // gain for controlling how quickly rangefinder range adjusts target altitude (lower means slower reaction)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef RANGEFINDER_FILT_DEFAULT
|
#ifndef RANGEFINDER_FILT_DEFAULT
|
||||||
# define RANGEFINDER_FILT_DEFAULT 0.5f // filter for rangefinder distance
|
# define RANGEFINDER_FILT_DEFAULT 0.5f // filter for rangefinder distance
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -54,7 +54,7 @@ enum tuning_func {
|
||||||
TUNING_DECLINATION = 38, // compass declination in radians
|
TUNING_DECLINATION = 38, // compass declination in radians
|
||||||
TUNING_CIRCLE_RATE = 39, // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
|
TUNING_CIRCLE_RATE = 39, // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
|
||||||
TUNING_ACRO_YAW_KP = 40, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
|
TUNING_ACRO_YAW_KP = 40, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
|
||||||
TUNING_RANGEFINDER_GAIN = 41, // rangefinder gain
|
TUNING_RANGEFINDER_GAIN = 41, // unused
|
||||||
TUNING_EKF_VERTICAL_POS = 42, // unused
|
TUNING_EKF_VERTICAL_POS = 42, // unused
|
||||||
TUNING_EKF_HORIZONTAL_POS = 43, // unused
|
TUNING_EKF_HORIZONTAL_POS = 43, // unused
|
||||||
TUNING_EKF_ACCEL_NOISE = 44, // unused
|
TUNING_EKF_ACCEL_NOISE = 44, // unused
|
||||||
|
|
|
@ -142,13 +142,6 @@ void Copter::tuning()
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
|
||||||
case TUNING_RANGEFINDER_GAIN:
|
|
||||||
// set rangefinder gain
|
|
||||||
g.rangefinder_gain.set(tuning_value);
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
case TUNING_RC_FEEL_RP:
|
case TUNING_RC_FEEL_RP:
|
||||||
attitude_control->set_input_tc(tuning_value);
|
attitude_control->set_input_tc(tuning_value);
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue