mirror of https://github.com/ArduPilot/ardupilot
Copter: update HeliQuad param file
fix servo range and reverse params
This commit is contained in:
parent
a2351bf99f
commit
2f26b3faa1
|
@ -29,7 +29,7 @@ ATC_RAT_YAW_VFF 0.0
|
|||
ATC_SLEW_YAW 6000.0
|
||||
FRAME_CLASS 13
|
||||
FRAME_TYPE 3
|
||||
H_COL_MAX 1850.0
|
||||
H_COL_MAX 1950.0
|
||||
H_COL_MID 1500.0
|
||||
H_COL_MIN 1350.0
|
||||
H_CYC_MAX 2500.0
|
||||
|
@ -49,11 +49,26 @@ IM_STAB_COL_1 0.0
|
|||
IM_STAB_COL_2 400.0
|
||||
IM_STAB_COL_3 600.0
|
||||
IM_STAB_COL_4 1000.0
|
||||
INS_ACCEL_FILTER 10.0
|
||||
INS_GYRO_FILTER 15.0
|
||||
PILOT_ACCEL_Z 250.0
|
||||
PILOT_VELZ_MAX 250.0
|
||||
POS_XY_P 0.7
|
||||
POS_Z_P 1.0
|
||||
RC_FEEL_RP 50.0
|
||||
SERVO1_MIN 950
|
||||
SERVO1_MAX 2050
|
||||
SERVO1_REVERSED 0
|
||||
SERVO2_MIN 950
|
||||
SERVO2_MAX 2050
|
||||
SERVO2_REVERSED 0
|
||||
SERVO3_MIN 950
|
||||
SERVO3_MAX 2050
|
||||
SERVO3_REVERSED 1
|
||||
SERVO4_MIN 950
|
||||
SERVO4_MAX 2050
|
||||
SERVO4_REVERSED 1
|
||||
SERVO4_TRIM 1570
|
||||
VEL_XY_I 0.7
|
||||
VEL_XY_P 0.3
|
||||
|
||||
|
|
Loading…
Reference in New Issue