2019-09-11 23:56:32 -03:00
|
|
|
# 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
|
|
|
|
#TERRAIN_ENABLE 0
|
|
|
|
|
|
|
|
# RC_SPEED at 7.1kHz for minimal radio interference, without
|
|
|
|
# being a multiple of IMU sample rate
|
|
|
|
RC_SPEED 7100
|
|
|
|
|
|
|
|
# toy mode setup
|
|
|
|
TMODE_ENABLE 2
|
|
|
|
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 63
|
|
|
|
TMODE_TMIN 0.9
|
|
|
|
|
|
|
|
# LEDs. pin0 is green, pin1 is red
|
2024-06-12 08:51:25 -03:00
|
|
|
RELAY1_PIN 0
|
|
|
|
RELAY2_PIN 1
|
|
|
|
RELAY1_DEFAULT 1
|
|
|
|
RELAY2_DEFAULT 1
|
2019-09-11 23:56:32 -03:00
|
|
|
|
|
|
|
AHRS_ORIENTATION 2
|
2021-12-04 00:22:56 -04:00
|
|
|
COMPASS_EXTERNAL 1
|
|
|
|
COMPASS_ORIENT 10
|
|
|
|
COMPASS_USE2 0
|
|
|
|
COMPASS_USE3 0
|
2019-09-11 23:56:32 -03:00
|
|
|
COMPASS_OFFS_MAX 2000
|
2021-12-04 00:22:56 -04:00
|
|
|
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
|
2019-09-11 23:56:32 -03:00
|
|
|
|
|
|
|
# battery setup
|
|
|
|
BATT_MONITOR 3
|
|
|
|
BATT_VOLT_PIN 9
|
|
|
|
BATT_VOLT_MULT 1
|
|
|
|
|
|
|
|
# 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
|
2022-10-24 23:44:56 -03:00
|
|
|
#BRD_SAFETY_DEFLT 0
|
2019-09-11 23:56:32 -03:00
|
|
|
|
|
|
|
SERIAL0_BAUD 115
|
|
|
|
SERIAL0_PROTOCOL 2
|
|
|
|
SERIAL1_BAUD 625000
|
|
|
|
SERIAL1_PROTOCOL 2
|
|
|
|
SERIAL2_PROTOCOL -1
|
|
|
|
SERIAL4_PROTOCOL -1
|
|
|
|
SERIAL5_PROTOCOL -1
|
|
|
|
|
|
|
|
# radio setup (auto-detect beken vs cc2500)
|
|
|
|
BRD_RADIO_TYPE 100
|
|
|
|
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 40
|
|
|
|
BRD_RADIO_TXMAX 5
|
|
|
|
BRD_RADIO_TXPOW 6
|
|
|
|
RSSI_TYPE 2
|
|
|
|
RSSI_CHANNEL 8
|
|
|
|
RSSI_CHAN_LOW 0
|
|
|
|
RSSI_CHAN_HIGH 200
|
|
|
|
|
|
|
|
|
|
|
|
# non-standard motor ordering
|
|
|
|
SERVO1_FUNCTION 35
|
|
|
|
SERVO2_FUNCTION 33
|
|
|
|
SERVO3_FUNCTION 34
|
|
|
|
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
|
|
|
|
TMODE_INAV_EN 1
|
|
|
|
TMODE_INAV_TC_Z 1.0
|
|
|
|
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 0.5
|
|
|
|
EK2_HGT_I_GATE 1000
|
|
|
|
EK2_ABIAS_P_NSE 0.01
|
|
|
|
|
|
|
|
|
|
|
|
# fence
|
|
|
|
FENCE_TYPE 3
|
|
|
|
FENCE_ENABLE 0
|
|
|
|
FENCE_RADIUS 100
|
|
|
|
FENCE_ALT_MAX 50
|
|
|
|
|
|
|
|
# arming
|
|
|
|
ARMING_CHECK 25586
|
|
|
|
DISARM_DELAY 8
|
|
|
|
|
|
|
|
# IMU
|
|
|
|
INS_FAST_SAMPLE 0
|
|
|
|
INS_GYRO_FILTER 20
|
|
|
|
LOG_BITMASK 65534
|
2022-04-13 00:44:27 -03:00
|
|
|
INS_HNTC2_ENABLE 1
|
|
|
|
INS_HNTC2_ATT 50
|
|
|
|
INS_HNTC2_BW 80
|
|
|
|
INS_HNTC2_FREQ 80
|
2019-09-11 23:56:32 -03:00
|
|
|
|
|
|
|
# profile parameters
|
|
|
|
TMODE_P1_ANG_MAX 2500
|
|
|
|
TMODE_P1_MODE 5
|
|
|
|
TMODE_P1_FEEL_RP 75
|
|
|
|
TMODE_P1_A_BAL_P 1
|
|
|
|
TMODE_P1_A_BAL_R 1
|
|
|
|
TMODE_P1_A_RP_P 8.0
|
|
|
|
TMODE_P1_A_RP_XP 0.3
|
|
|
|
TMODE_P1_A_THR_M 0
|
|
|
|
TMODE_P1_A_TRNR 2
|
|
|
|
TMODE_P1_A_YAW_P 4.0
|
|
|
|
TMODE_P1_A_Y_XP 0
|
|
|
|
TMODE_P1_LTR_SPD 800
|
|
|
|
TMODE_P1_LTR_JRK 4000
|
|
|
|
TMODE_P1_LTR_MNA 250
|
|
|
|
TMODE_P1_LTR_MXA 800
|
|
|
|
TMODE_P1_PL_V_UP 250
|
|
|
|
TMODE_P1_WP_RAD 200
|
|
|
|
TMODE_P1_WP_SPD 750
|
|
|
|
TMODE_P1_WP_V_DN 150
|
|
|
|
TMODE_P1_WP_V_UP 250
|
|
|
|
TMODE_P1_WP_RAD 200
|
|
|
|
TMODE_P1_WP_SPD 750
|
|
|
|
TMODE_P1_WP_V_DN 150
|
|
|
|
TMODE_P1_WP_V_UP 250
|
|
|
|
TMODE_P1_WP_XL 100
|
|
|
|
TMODE_P1_WP_XL_Z 100
|
|
|
|
TMODE_P1_XL_P_MX 108000
|
|
|
|
TMODE_P1_XL_R_MX 108000
|
|
|
|
TMODE_P1_XL_Y_MX 36000
|
|
|
|
|
|
|
|
TMODE_P2_ANG_MAX 3500
|
|
|
|
TMODE_P2_MODE 5
|
|
|
|
TMODE_P2_FEEL_RP 100
|
|
|
|
TMODE_P2_A_BAL_P 1
|
|
|
|
TMODE_P2_A_BAL_R 1
|
|
|
|
TMODE_P2_A_RP_P 8.0
|
|
|
|
TMODE_P2_A_RP_XP 0.3
|
|
|
|
TMODE_P2_A_THR_M 0
|
|
|
|
TMODE_P2_A_TRNR 2
|
|
|
|
TMODE_P2_A_YAW_P 4.0
|
|
|
|
TMODE_P2_A_Y_XP 0
|
|
|
|
TMODE_P2_LTR_SPD 800
|
|
|
|
TMODE_P2_LTR_JRK 4000
|
|
|
|
TMODE_P2_LTR_MNA 250
|
|
|
|
TMODE_P2_LTR_MXA 800
|
|
|
|
TMODE_P2_PL_V_UP 250
|
|
|
|
TMODE_P2_WP_RAD 200
|
|
|
|
TMODE_P2_WP_SPD 750
|
|
|
|
TMODE_P2_WP_V_DN 150
|
|
|
|
TMODE_P2_WP_V_UP 250
|
|
|
|
TMODE_P2_WP_RAD 200
|
|
|
|
TMODE_P2_WP_SPD 750
|
|
|
|
TMODE_P2_WP_V_DN 150
|
|
|
|
TMODE_P2_WP_V_UP 250
|
|
|
|
TMODE_P2_WP_XL 100
|
|
|
|
TMODE_P2_WP_XL_Z 100
|
|
|
|
TMODE_P2_XL_P_MX 108000
|
|
|
|
TMODE_P2_XL_R_MX 108000
|
|
|
|
TMODE_P2_XL_Y_MX 36000
|
|
|
|
|
|
|
|
TMODE_P3_MODE 2
|
|
|
|
TMODE_P3_ANG_MAX 2500
|
|
|
|
TMODE_P3_FEEL_RP 75
|
|
|
|
TMODE_P3_A_BAL_P 1
|
|
|
|
TMODE_P3_A_BAL_R 1
|
|
|
|
TMODE_P3_A_RP_P 8.0
|
|
|
|
TMODE_P3_A_RP_XP 0.3
|
|
|
|
TMODE_P3_A_THR_M 0
|
|
|
|
TMODE_P3_A_TRNR 2
|
|
|
|
TMODE_P3_A_YAW_P 4.0
|
|
|
|
TMODE_P3_A_Y_XP 0
|
|
|
|
TMODE_P3_LTR_SPD 800
|
|
|
|
TMODE_P3_LTR_JRK 4000
|
|
|
|
TMODE_P3_LTR_MNA 250
|
|
|
|
TMODE_P3_LTR_MXA 800
|
|
|
|
TMODE_P3_PL_V_UP 250
|
|
|
|
TMODE_P3_WP_RAD 200
|
|
|
|
TMODE_P3_WP_SPD 750
|
|
|
|
TMODE_P3_WP_V_DN 150
|
|
|
|
TMODE_P3_WP_V_UP 250
|
|
|
|
TMODE_P3_WP_RAD 200
|
|
|
|
TMODE_P3_WP_SPD 750
|
|
|
|
TMODE_P3_WP_V_DN 150
|
|
|
|
TMODE_P3_WP_V_UP 250
|
|
|
|
TMODE_P3_WP_XL 100
|
|
|
|
TMODE_P3_WP_XL_Z 100
|
|
|
|
TMODE_P3_XL_P_MX 108000
|
|
|
|
TMODE_P3_XL_R_MX 108000
|
|
|
|
TMODE_P3_XL_Y_MX 36000
|
|
|
|
|
|
|
|
TMODE_P4_MODE 2
|
|
|
|
TMODE_P4_ANG_MAX 3500
|
|
|
|
TMODE_P4_FEEL_RP 100
|
|
|
|
TMODE_P4_A_BAL_P 1
|
|
|
|
TMODE_P4_A_BAL_R 1
|
|
|
|
TMODE_P4_A_RP_P 8.0
|
|
|
|
TMODE_P4_A_RP_XP 0.3
|
|
|
|
TMODE_P4_A_THR_M 0
|
|
|
|
TMODE_P4_A_TRNR 2
|
|
|
|
TMODE_P4_A_YAW_P 4.0
|
|
|
|
TMODE_P4_A_Y_XP 0
|
|
|
|
TMODE_P4_LTR_SPD 800
|
|
|
|
TMODE_P4_LTR_JRK 4000
|
|
|
|
TMODE_P4_LTR_MNA 250
|
|
|
|
TMODE_P4_LTR_MXA 800
|
|
|
|
TMODE_P4_PL_V_UP 250
|
|
|
|
TMODE_P4_WP_RAD 200
|
|
|
|
TMODE_P4_WP_SPD 750
|
|
|
|
TMODE_P4_WP_V_DN 150
|
|
|
|
TMODE_P4_WP_V_UP 250
|
|
|
|
TMODE_P4_WP_RAD 200
|
|
|
|
TMODE_P4_WP_SPD 750
|
|
|
|
TMODE_P4_WP_V_DN 150
|
|
|
|
TMODE_P4_WP_V_UP 250
|
|
|
|
TMODE_P4_WP_XL 100
|
|
|
|
TMODE_P4_WP_XL_Z 100
|
|
|
|
TMODE_P4_XL_P_MX 108000
|
|
|
|
TMODE_P4_XL_R_MX 108000
|
|
|
|
TMODE_P4_XL_Y_MX 36000
|
|
|
|
|
|
|
|
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.46
|
|
|
|
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.045
|
|
|
|
MOT_SPIN_MIN 0.045
|
|
|
|
MOT_SPIN_MAX 1.0
|
|
|
|
MOT_SPOOL_TIME 0
|
|
|
|
MOT_HOVER_LEARN 1
|
|
|
|
|
|
|
|
# control inputs
|
|
|
|
PILOT_THR_BHV 3
|
|
|
|
PILOT_ACCEL_Z 400
|
|
|
|
PILOT_VELZ_MAX 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 control
|
|
|
|
PSC_POSXY_P 0.7
|
|
|
|
PSC_VELXY_I 0.3
|
|
|
|
PSC_VELXY_P 0.6
|
2021-08-03 03:17:14 -03:00
|
|
|
PSC_VELXY_FLTE 1.0
|
2019-09-11 23:56:32 -03:00
|
|
|
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
|
2024-03-15 01:54:39 -03:00
|
|
|
GPS1_TYPE 2
|
2019-09-11 23:56:32 -03:00
|
|
|
GPS_HDOP_GOOD 160
|
|
|
|
|
|
|
|
# throw mode
|
|
|
|
THROW_NEXTMODE 5
|
|
|
|
|
|
|
|
# disable optical flow
|
|
|
|
FLOW_ENABLE 0
|
|
|
|
|
|
|
|
# flip params
|
|
|
|
FLIP_RAMP_CD 500
|
|
|
|
FLIP_RAMP_MS 350
|
|
|
|
FLIP_ROT_RATE 3000
|
|
|
|
FLIP_ACCEL_MAX 3000
|
|
|
|
|
|
|
|
# extra parameters for GPS
|
|
|
|
BRD_RADIO_TYPE 2
|
|
|
|
BRD_RADIO_ABLVL 40
|
|
|
|
|
|
|
|
TMODE_ACTION1 2
|
|
|
|
TMODE_ACTION2 16
|
|
|
|
TMODE_MODE1 5
|
|
|
|
TMODE_MODE2 2
|
|
|
|
TMODE_TOFF_HGT 1.2
|
|
|
|
TMODE_TOFF_TIME 5.0
|
|
|
|
TMODE_TOFF_ACC 75
|
|
|
|
|
|
|
|
ATC_ACCEL_P_MAX 108000
|
|
|
|
ATC_ACCEL_R_MAX 108000
|
|
|
|
MOT_SPOOL_TIME 0.0500
|
|
|
|
MOT_THST_HOVER 0.3398
|
|
|
|
PSC_ACCZ_FILT 5.0000
|
|
|
|
PSC_ACCZ_P 1.0000
|
|
|
|
PSC_POSZ_P 0.5000
|
|
|
|
PSC_VELZ_P 1.0000
|
|
|
|
RC_FEEL_RP 75.0000
|
|
|
|
|
|
|
|
# default to GPS frame
|
|
|
|
SYSID_SW_TYPE 100
|
|
|
|
|