Tools: update EnRoute EX700 parameters

This commit is contained in:
Randy Mackay 2016-08-04 16:56:46 +09:00
parent b6c27b58a8
commit 3b86ef71ca

View File

@ -1,10 +1,23 @@
#NOTE: EnRoute EX700 parameter defaults (Copter-3.4)
ACRO_YAW_P,3.0
ANGLE_MAX,3000
AUTOTUNE_AGGR,0.05
AUTOTUNE_AGGR,0.075
ATC_ACCEL_P_MAX,58000
ATC_ACCEL_R_MAX,50000
ATC_ACCEL_Y_MAX,7500
ATC_ACCEL_Y_MAX,10000
ATC_ANG_PIT_P,4.10
ATC_ANG_RLL_P,5.66
ATC_ANG_YAW_P,5.39
ATC_RAT_PIT_D,0.0089
ATC_RAT_PIT_FILT,10.0
ATC_RAT_PIT_I,0.1139
ATC_RAT_PIT_P,0.1139
ATC_RAT_RLL_D,0.0043
ATC_RAT_RLL_FILT,10.0
ATC_RAT_RLL_I,0.0700
ATC_RAT_RLL_P,0.0700
ATC_RAT_YAW_I,0.044
ATC_RAT_YAW_P,0.441
BATT_MONITOR,4
BATT_AMP_PERVOLT,54.64
BATT_CAPACITY,13500