mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Copter: add params file for Iris
This commit is contained in:
parent
65adb78f31
commit
36b9700537
35
Tools/Frame_params/Iris.param
Normal file
35
Tools/Frame_params/Iris.param
Normal file
@ -0,0 +1,35 @@
|
||||
AMP_PER_VOLT,17
|
||||
BATT_MONITOR,4
|
||||
BATT_CURR_PIN,3
|
||||
BATT_VOLT_PIN,2
|
||||
COMPASS_ORIENT,8
|
||||
FLTMODE1,0
|
||||
FLTMODE2,0
|
||||
FLTMODE3,0
|
||||
FLTMODE4,5
|
||||
FLTMODE5,0
|
||||
FLTMODE6,3
|
||||
FRAME,2
|
||||
INS_PRODUCT_ID,5
|
||||
MOT_SPIN_ARMED,127
|
||||
RATE_PIT_D,0.008
|
||||
RATE_PIT_I,0.25
|
||||
RATE_PIT_P,0.17
|
||||
RATE_RLL_D,0.008
|
||||
RATE_RLL_I,0.25
|
||||
RATE_RLL_P,0.17
|
||||
RATE_YAW_D,0
|
||||
RATE_YAW_I,0.02
|
||||
RATE_YAW_IMAX,4800
|
||||
RATE_YAW_P,0.16
|
||||
RELAY_PIN,111
|
||||
RTL_LOIT_TIME,2000
|
||||
STB_PIT_P,3.8
|
||||
STB_RLL_P,3.8
|
||||
STB_YAW_P,2.5
|
||||
THR_MID,650
|
||||
THR_RATE_P,5
|
||||
VOLT_DIVIDER,10.1
|
||||
WPNAV_ACCEL,200
|
||||
WPNAV_LOIT_SPEED,1000
|
||||
WPNAV_SPEED,700
|
Loading…
Reference in New Issue
Block a user