mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Frame: new Bebop default parameters
This commit is contained in:
parent
8a66c9c2ed
commit
041dd3c855
@ -1,26 +1,28 @@
|
||||
#NOTE: Bebop default parameters
|
||||
|
||||
ATC_ACCEL_P_MAX,150000
|
||||
ATC_ACCEL_R_MAX,150000
|
||||
ATC_ACCEL_Y_MAX,27000
|
||||
#NOTE: Bebop default parameters
|
||||
ATC_ACCEL_P_MAX,220000
|
||||
ATC_ACCEL_R_MAX,220000
|
||||
ATC_ACCEL_Y_MAX,56000
|
||||
INS_GYRO_FILTER,40
|
||||
MOT_THST_EXPO,0.6
|
||||
MOT_THST_EXPO,0.05
|
||||
MOT_THST_MAX,1.00
|
||||
RATE_PIT_D,0.0025
|
||||
MOT_YAW_HEADROOM,200
|
||||
POS_XY_P,1
|
||||
RATE_PIT_D,0.0022
|
||||
RATE_PIT_FILT_HZ,40
|
||||
RATE_PIT_I,0.15
|
||||
RATE_PIT_I,0.126
|
||||
RATE_PIT_IMAX,2000
|
||||
RATE_PIT_P,0.15
|
||||
RATE_RLL_D,0.002
|
||||
RATE_PIT_P,0.126
|
||||
RATE_RLL_D,0.0005
|
||||
RATE_RLL_FILT_HZ,40
|
||||
RATE_RLL_I,0.1
|
||||
RATE_RLL_I,0.11
|
||||
RATE_RLL_IMAX,2000
|
||||
RATE_RLL_P,0.1
|
||||
RATE_RLL_P,0.11
|
||||
RATE_YAW_D,0
|
||||
RATE_YAW_FILT_HZ,4
|
||||
RATE_YAW_I,0.04
|
||||
RATE_YAW_FILT_HZ,3.0
|
||||
RATE_YAW_I,0.103
|
||||
RATE_YAW_IMAX,1000
|
||||
RATE_YAW_P,0.4
|
||||
STB_PIT_P,6
|
||||
STB_RLL_P,6
|
||||
STB_YAW_P,4.5
|
||||
RATE_YAW_P,1.03
|
||||
STB_PIT_P,15
|
||||
STB_RLL_P,10
|
||||
STB_YAW_P,12
|
||||
THR_MIN,130
|
||||
|
Loading…
Reference in New Issue
Block a user