mirror of https://github.com/ArduPilot/ardupilot
Copter: ch6 tuning of RC_FEEL_RP
This commit is contained in:
parent
e89600afe3
commit
c56f521897
|
@ -1562,6 +1562,11 @@ static void tuning(){
|
||||||
ahrs.get_NavEKF()._accNoise = tuning_value;
|
ahrs.get_NavEKF()._accNoise = tuning_value;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case CH6_RC_FEEL_RP:
|
||||||
|
// roll-pitch input smoothing
|
||||||
|
g.rc_feel_rp = g.rc_6.control_in / 10;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -147,6 +147,7 @@
|
||||||
#define CH6_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
|
#define CH6_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
|
||||||
#define CH6_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
|
#define CH6_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
|
||||||
#define CH6_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)
|
#define CH6_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)
|
||||||
|
#define CH6_RC_FEEL_RP 45 // roll-pitch input smoothing
|
||||||
|
|
||||||
// Acro Trainer types
|
// Acro Trainer types
|
||||||
#define ACRO_TRAINER_DISABLED 0
|
#define ACRO_TRAINER_DISABLED 0
|
||||||
|
|
Loading…
Reference in New Issue