mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Frame_params: bring 2450 params in line with release
This commit is contained in:
parent
c708201fc6
commit
360a8d99bf
@ -17,7 +17,7 @@ TMODE_ACTION3 18
|
|||||||
TMODE_ACTION4 0
|
TMODE_ACTION4 0
|
||||||
TMODE_ACTION5 0
|
TMODE_ACTION5 0
|
||||||
TMODE_ACTION6 0
|
TMODE_ACTION6 0
|
||||||
TMODE_FLAGS 15
|
TMODE_FLAGS 23
|
||||||
TMODE_TMIN 0.9
|
TMODE_TMIN 0.9
|
||||||
|
|
||||||
# LEDs. pin54 is green, pin55 is red
|
# LEDs. pin54 is green, pin55 is red
|
||||||
@ -49,9 +49,9 @@ COMPASS_PMOT_EN 1
|
|||||||
COMPASS_PMOT_EXP 0.65
|
COMPASS_PMOT_EXP 0.65
|
||||||
COMPASS_LEARN 2
|
COMPASS_LEARN 2
|
||||||
|
|
||||||
#BRD_SER1_RTSCTS 0
|
BRD_SER1_RTSCTS 0
|
||||||
#BRD_SER2_RTSCTS 0
|
BRD_SER2_RTSCTS 0
|
||||||
#BRD_SAFETYENABLE 0
|
BRD_SAFETYENABLE 0
|
||||||
|
|
||||||
SERIAL0_PROTOCOL 2
|
SERIAL0_PROTOCOL 2
|
||||||
SERIAL1_BAUD 625000
|
SERIAL1_BAUD 625000
|
||||||
@ -76,10 +76,10 @@ RSSI_CHAN_HIGH 200
|
|||||||
|
|
||||||
|
|
||||||
# non-standard motor ordering
|
# non-standard motor ordering
|
||||||
SERVO1_FUNCTION 35
|
SERVO1_FUNCTION 36
|
||||||
SERVO2_FUNCTION 34
|
SERVO2_FUNCTION 33
|
||||||
SERVO3_FUNCTION 33
|
SERVO3_FUNCTION 34
|
||||||
SERVO4_FUNCTION 36
|
SERVO4_FUNCTION 35
|
||||||
|
|
||||||
# H class quad
|
# H class quad
|
||||||
FRAME_CLASS 1
|
FRAME_CLASS 1
|
||||||
@ -87,6 +87,7 @@ FRAME_TYPE 1
|
|||||||
|
|
||||||
# enable EK2
|
# enable EK2
|
||||||
EK2_ENABLE 1
|
EK2_ENABLE 1
|
||||||
|
EK2_CHECK_SCALE 150
|
||||||
|
|
||||||
# EK3 disabled for flight
|
# EK3 disabled for flight
|
||||||
AHRS_EKF_TYPE 2
|
AHRS_EKF_TYPE 2
|
||||||
@ -105,6 +106,7 @@ FENCE_TYPE 3
|
|||||||
FENCE_ENABLE 0
|
FENCE_ENABLE 0
|
||||||
FENCE_RADIUS 100
|
FENCE_RADIUS 100
|
||||||
FENCE_ALT_MAX 50
|
FENCE_ALT_MAX 50
|
||||||
|
FENCE_MARGIN 3
|
||||||
|
|
||||||
# arming
|
# arming
|
||||||
ARMING_CHECK 32767
|
ARMING_CHECK 32767
|
||||||
@ -163,7 +165,7 @@ FLTMODE6 2
|
|||||||
# failsafes
|
# failsafes
|
||||||
FS_THR_ENABLE 1
|
FS_THR_ENABLE 1
|
||||||
FS_BATT_ENABLE 2
|
FS_BATT_ENABLE 2
|
||||||
FS_BATT_VOLTAGE 3.4
|
FS_BATT_VOLTAGE 3.43
|
||||||
FS_GCS_ENABLE 0
|
FS_GCS_ENABLE 0
|
||||||
|
|
||||||
# baro
|
# baro
|
||||||
@ -171,7 +173,7 @@ TCAL_ENABLED 2
|
|||||||
TCAL_BARO_EXP 1.2
|
TCAL_BARO_EXP 1.2
|
||||||
|
|
||||||
# landing
|
# landing
|
||||||
LAND_SPEED_HIGH 150
|
LAND_SPEED_HIGH 350
|
||||||
|
|
||||||
# logging
|
# logging
|
||||||
LOG_BACKEND_TYPE 2
|
LOG_BACKEND_TYPE 2
|
||||||
@ -231,3 +233,10 @@ GPS_HDOP_GOOD 160
|
|||||||
|
|
||||||
# throw mode
|
# throw mode
|
||||||
THROW_NEXTMODE 5
|
THROW_NEXTMODE 5
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user