Copter: remove unused Ch6 EKF tuning options

This commit is contained in:
Randy Mackay 2020-04-21 19:26:15 +09:00
parent 913e5a23fe
commit f3989cae4c
2 changed files with 3 additions and 34 deletions

View File

@ -57,9 +57,9 @@ enum tuning_func {
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, // rangefinder gain
TUNING_EKF_VERTICAL_POS = 42, // EKF's baro vs accel (higher rely on accels more, baro impact is reduced). Range should be 0.2 ~ 4.0? 2.0 is default TUNING_EKF_VERTICAL_POS = 42, // unused
TUNING_EKF_HORIZONTAL_POS = 43, // EKF's gps vs accel (higher rely on accels more, gps impact is reduced). Range should be 1.0 ~ 3.0? 1.5 is default TUNING_EKF_HORIZONTAL_POS = 43, // unused
TUNING_EKF_ACCEL_NOISE = 44, // EKF's accel noise (lower means trust accels more, gps & baro less). Range should be 0.02 ~ 0.5 0.5 is default (but very robust at that level) TUNING_EKF_ACCEL_NOISE = 44, // unused
TUNING_RC_FEEL_RP = 45, // roll-pitch input smoothing TUNING_RC_FEEL_RP = 45, // roll-pitch input smoothing
TUNING_RATE_PITCH_KP = 46, // body frame pitch rate controller's P term TUNING_RATE_PITCH_KP = 46, // body frame pitch rate controller's P term
TUNING_RATE_PITCH_KI = 47, // body frame pitch rate controller's I term TUNING_RATE_PITCH_KI = 47, // body frame pitch rate controller's I term

View File

@ -149,37 +149,6 @@ void Copter::tuning()
break; break;
#endif #endif
#if 0
// disabled for now - we need accessor functions
case TUNING_EKF_VERTICAL_POS:
// Tune the EKF that is being used
// EKF's baro vs accel (higher rely on accels more, baro impact is reduced)
if (!ahrs.get_NavEKF2().enabled()) {
ahrs.get_NavEKF()._gpsVertPosNoise = tuning_value;
} else {
ahrs.get_NavEKF2()._gpsVertPosNoise = tuning_value;
}
break;
case TUNING_EKF_HORIZONTAL_POS:
// EKF's gps vs accel (higher rely on accels more, gps impact is reduced)
if (!ahrs.get_NavEKF2().enabled()) {
ahrs.get_NavEKF()._gpsHorizPosNoise = tuning_value;
} else {
ahrs.get_NavEKF2()._gpsHorizPosNoise = tuning_value;
}
break;
case TUNING_EKF_ACCEL_NOISE:
// EKF's accel noise (lower means trust accels more, gps & baro less)
if (!ahrs.get_NavEKF2().enabled()) {
ahrs.get_NavEKF()._accNoise = tuning_value;
} else {
ahrs.get_NavEKF2()._accNoise = 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;