mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Frame_params: added SkyViper 2450GPS params for ChibiOS
This commit is contained in:
parent
21f40da510
commit
40ba4645e6
233
Tools/Frame_params/SkyViper-2450GPS/defaults.parm
Normal file
233
Tools/Frame_params/SkyViper-2450GPS/defaults.parm
Normal file
@ -0,0 +1,233 @@
|
||||
# defaults for SkyRocket streaming GPS board
|
||||
BRD_TYPE 21
|
||||
BRD_IO_ENABLE 0
|
||||
MOT_PWM_TYPE 3
|
||||
MOT_PWM_MIN 1000
|
||||
MOT_PWM_MAX 2000
|
||||
RC_SPEED 16000
|
||||
# TERRAIN_ENABLE 0
|
||||
|
||||
# toy mode setup
|
||||
TMODE_ENABLE 1
|
||||
TMODE_MODE1 5
|
||||
TMODE_MODE2 2
|
||||
TMODE_ACTION1 2
|
||||
TMODE_ACTION2 1
|
||||
TMODE_ACTION3 18
|
||||
TMODE_ACTION4 0
|
||||
TMODE_ACTION5 0
|
||||
TMODE_ACTION6 0
|
||||
TMODE_FLAGS 15
|
||||
TMODE_TMIN 0.9
|
||||
|
||||
# LEDs. pin54 is green, pin55 is red
|
||||
RELAY_PIN 54
|
||||
RELAY_PIN2 55
|
||||
RELAY_DEFAULT 1
|
||||
|
||||
AHRS_ORIENTATION 12
|
||||
COMPASS_EXTERNAL 1
|
||||
COMPASS_ORIENT 10
|
||||
COMPASS_USE2 0
|
||||
COMPASS_USE3 0
|
||||
COMPASS_OFFS_MAX 2000
|
||||
COMPASS_DIA_X 1.20
|
||||
COMPASS_DIA_Y 1.11
|
||||
COMPASS_DIA_Z 0.89
|
||||
COMPASS_ODI_X -0.051
|
||||
COMPASS_ODI_Y 0.141
|
||||
COMPASS_ODI_Z 0.091
|
||||
|
||||
# battery setup
|
||||
BATT_MONITOR 3
|
||||
BATT_VOLT_PIN 4
|
||||
BATT_VOLT_MULT 0.8485
|
||||
|
||||
# motor compensation
|
||||
COMPASS_MOTCT 3
|
||||
COMPASS_PMOT_EN 1
|
||||
COMPASS_PMOT_EXP 0.65
|
||||
COMPASS_LEARN 2
|
||||
|
||||
#BRD_SER1_RTSCTS 0
|
||||
#BRD_SER2_RTSCTS 0
|
||||
#BRD_SAFETYENABLE 0
|
||||
|
||||
SERIAL0_PROTOCOL 2
|
||||
SERIAL1_BAUD 625000
|
||||
SERIAL1_PROTOCOL 2
|
||||
SERIAL2_BAUD 115
|
||||
SERIAL2_PROTOCOL 2
|
||||
|
||||
# radio setup
|
||||
BRD_RADIO_TYPE 1
|
||||
BRD_RADIO_PROT 1
|
||||
BRD_RADIO_PPSCH 8
|
||||
BRD_RADIO_SIGCH 9
|
||||
BRD_RADIO_TPPSCH 10
|
||||
BRD_RADIO_TSIGCH 11
|
||||
BRD_RADIO_TELEM 1
|
||||
BRD_RADIO_ABTIME 10
|
||||
BRD_RADIO_ABLVL 25
|
||||
RSSI_TYPE 2
|
||||
RSSI_CHANNEL 8
|
||||
RSSI_CHAN_LOW 0
|
||||
RSSI_CHAN_HIGH 200
|
||||
|
||||
|
||||
# non-standard motor ordering
|
||||
SERVO1_FUNCTION 35
|
||||
SERVO2_FUNCTION 34
|
||||
SERVO3_FUNCTION 33
|
||||
SERVO4_FUNCTION 36
|
||||
|
||||
# H class quad
|
||||
FRAME_CLASS 1
|
||||
FRAME_TYPE 1
|
||||
|
||||
# enable EK2
|
||||
EK2_ENABLE 1
|
||||
|
||||
# EK3 disabled for flight
|
||||
AHRS_EKF_TYPE 2
|
||||
EK3_ENABLE 0
|
||||
#EK3_CHECK_SCALE 120
|
||||
#EK3_ACC_BIAS_LIM 1.0
|
||||
#EK3_ABIAS_P_NSE 0.01
|
||||
#EK3_MAG_CAL = 0
|
||||
|
||||
# setup EK2 limits
|
||||
EK2_CHECK_SCALE 120
|
||||
EK2_ALT_M_NSE 2.0
|
||||
|
||||
# fence
|
||||
FENCE_TYPE 3
|
||||
FENCE_ENABLE 0
|
||||
FENCE_RADIUS 100
|
||||
FENCE_ALT_MAX 50
|
||||
|
||||
# arming
|
||||
ARMING_CHECK 32767
|
||||
DISARM_DELAY 8
|
||||
|
||||
# IMU
|
||||
INS_FAST_SAMPLE 1
|
||||
INS_GYRO_FILTER 20
|
||||
LOG_BITMASK 65534
|
||||
INS_NOTCH_ENABLE 1
|
||||
INS_NOTCH_ATT 30
|
||||
INS_NOTCH_BW 60
|
||||
INS_NOTCH_FREQ 80
|
||||
|
||||
# rate controllers
|
||||
ANGLE_MAX 3500
|
||||
ATC_ACCEL_R_MAX 160000
|
||||
ATC_ACCEL_P_MAX 160000
|
||||
ATC_ACCEL_Y_MAX 54000
|
||||
ATC_ANG_PIT_P 8.0
|
||||
ATC_ANG_RLL_P 8.0
|
||||
ATC_ANG_YAW_P 7.16
|
||||
ATC_RAT_PIT_D 0.0069
|
||||
ATC_RAT_PIT_FILT 10
|
||||
ATC_RAT_PIT_IMAX 0.5
|
||||
ATC_RAT_PIT_I 0.0834
|
||||
ATC_RAT_PIT_P 0.0834
|
||||
ATC_RAT_RLL_D 0.007
|
||||
ATC_RAT_RLL_FILT 10
|
||||
ATC_RAT_RLL_I 0.0966
|
||||
ATC_RAT_RLL_P 0.0966
|
||||
ATC_RAT_RLL_IMAX 0.5
|
||||
ATC_RAT_YAW_P 0.6887
|
||||
ATC_RAT_YAW_I 0.0689
|
||||
ATC_RAT_YAW_IMAX 0.3
|
||||
ATC_RAT_YAW_D 0.0
|
||||
ATC_RAT_YAW_FILT 4.5125
|
||||
ATC_SLEW_YAW 3250
|
||||
ATC_THR_MIX_MAN 4
|
||||
ATC_THR_MIX_MAX 0.9
|
||||
|
||||
# tuning
|
||||
ACRO_RP_EXPO 0.3
|
||||
ACRO_RP_P 8
|
||||
ACRO_YAW_P 4
|
||||
|
||||
# flight modes
|
||||
FLTMODE_CH 0
|
||||
FLTMODE1 2
|
||||
FLTMODE2 2
|
||||
FLTMODE3 2
|
||||
FLTMODE4 2
|
||||
FLTMODE5 2
|
||||
FLTMODE6 2
|
||||
|
||||
# failsafes
|
||||
FS_THR_ENABLE 1
|
||||
FS_BATT_ENABLE 2
|
||||
FS_BATT_VOLTAGE 3.4
|
||||
FS_GCS_ENABLE 0
|
||||
|
||||
# baro
|
||||
TCAL_ENABLED 2
|
||||
TCAL_BARO_EXP 1.2
|
||||
|
||||
# landing
|
||||
LAND_SPEED_HIGH 150
|
||||
|
||||
# logging
|
||||
LOG_BACKEND_TYPE 2
|
||||
LOG_FILE_BUFSIZE 1
|
||||
|
||||
# voltages
|
||||
MOT_BAT_VOLT_MAX 4.2
|
||||
MOT_BAT_VOLT_MIN 3.3
|
||||
MOT_THST_HOVER 0.3514
|
||||
MOT_THST_EXPO -0.56
|
||||
MOT_SPIN_ARM 0.03
|
||||
MOT_SPIN_MIN 0.03
|
||||
MOT_SPIN_MAX 1.0
|
||||
MOT_SPOOL_TIME 0
|
||||
MOT_HOVER_LEARN 1
|
||||
|
||||
# control inputs
|
||||
PILOT_THR_BHV 3
|
||||
PILOT_ACCEL_Z 400
|
||||
PILOT_SPEED_DN 500
|
||||
RC_FEEL_RP 50
|
||||
RC1_MIN 1000
|
||||
RC1_MAX 2000
|
||||
RC2_MIN 1000
|
||||
RC2_MAX 2000
|
||||
RC3_MIN 1000
|
||||
RC3_MAX 2000
|
||||
RC4_MIN 1000
|
||||
RC4_MAX 2000
|
||||
RC3_TRIM 1500
|
||||
RTL_ALT 400
|
||||
GND_EFFECT_COMP 1
|
||||
|
||||
# deadzones, with auto-trim
|
||||
RC1_DZ 15
|
||||
RC2_DZ 15
|
||||
RC3_DZ 15
|
||||
RC4_DZ 15
|
||||
|
||||
# pos control
|
||||
POS_XY_P 0.7
|
||||
VEL_XY_I 0.3
|
||||
VEL_XY_P 0.6
|
||||
VEL_XY_FILT_HZ 1.0
|
||||
WPNAV_LOIT_JERK 4000
|
||||
WPNAV_LOIT_MAXA 800
|
||||
WPNAV_LOIT_MINA 250
|
||||
WPNAV_LOIT_SPEED 800
|
||||
WPNAV_SPEED 750
|
||||
RTL_SPEED 600
|
||||
|
||||
# GPS
|
||||
GPS_NAVFILTER 6
|
||||
GPS_SAVE_CFG 2
|
||||
GPS_TYPE 2
|
||||
GPS_HDOP_GOOD 160
|
||||
|
||||
# throw mode
|
||||
THROW_NEXTMODE 5
|
Loading…
Reference in New Issue
Block a user