From 8a07701d070e8e88cd614ebbb57fdb1d8e7f1dd4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Aug 2014 14:45:29 +0900 Subject: [PATCH] Copter: remove ch6 tuning of INAV_TC Users normally never change these parameters and if by chance they do want to, they can set them before flying --- ArduCopter/ArduCopter.pde | 6 ------ ArduCopter/Parameters.pde | 2 +- ArduCopter/defines.h | 2 +- 3 files changed, 2 insertions(+), 8 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 80621d9cbd..a869bcc5a7 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1556,12 +1556,6 @@ static void tuning(){ ahrs._kp.set(tuning_value); break; - case CH6_INAV_TC: - // To-Do: allowing tuning TC for xy and z separately - inertial_nav.set_time_constant_xy(tuning_value); - inertial_nav.set_time_constant_z(tuning_value); - break; - case CH6_DECLINATION: // set declination to +-20degrees compass.set_declination(ToRad((2.0f * g.rc_6.control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index c5cf30f9db..471166a4fd 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -361,7 +361,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @DisplayName: Channel 6 Tuning // @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob // @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,14:Altitude Hold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,42:Loiter Speed,12:Loiter Pos kP,22:Loiter Rate kP,28:Loiter Rate kI,23:Loiter Rate kD,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,9:Relay On/Off,13:Heli Ext Gyro,17:OF Loiter kP,18:OF Loiter kI,19:OF Loiter kD,30:AHRS Yaw kP,31:AHRS kP,32:INAV_TC,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 + // @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,14:Altitude Hold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,42:Loiter Speed,12:Loiter Pos kP,22:Loiter Rate kP,28:Loiter Rate kI,23:Loiter Rate kD,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,9:Relay On/Off,13:Heli Ext Gyro,17:OF Loiter kP,18:OF Loiter kI,19:OF Loiter kD,30:AHRS Yaw kP,31:AHRS kP,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 GSCALAR(radio_tuning, "TUNE", 0), // @Param: TUNE_LOW diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 9b8343a2e6..03b93145fb 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -133,7 +133,7 @@ #define CH6_OPTFLOW_KD 19 // optical flow loiter controller's D term (position error to tilt angle) #define CH6_AHRS_YAW_KP 30 // ahrs's compass effect on yaw angle (0 = very low, 1 = very high) #define CH6_AHRS_KP 31 // accelerometer effect on roll/pitch angle (0=low) -#define CH6_INAV_TC 32 // inertial navigation baro/accel and gps/accel time constant (1.5 = strong baro/gps correction on accel estimatehas very strong does not correct accel estimate, 7 = very weak correction) +#define CH6_INAV_TC 32 // deprecated -- remove #define CH6_DECLINATION 38 // compass declination in radians #define CH6_CIRCLE_RATE 39 // circle turn rate in degrees (hard coded to about 45 degrees in either direction) #define CH6_SONAR_GAIN 41 // sonar gain