mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-12 01:27:35 +08:00
Mantis: add RC hacks
This changes the way RC is handled for the Mantis: - The RC values are re-written when arriving over MAVLink. They are rescaled from 0..4095 to 1000..2000 and the channel bits added to separate channels. This makes the downstream handling easier. - Gimbal pitch is moved from Aux1 to Aux2 as that should be the default. - Aux3 and Aux4 are used for the photo and video trigger. - The speed button is used as the FLTMODE channel and set to switch between POSCTL and ALTCTL.
This commit is contained in:
@@ -33,12 +33,13 @@ param set-default CBRK_SUPPLY_CHK 894281
|
||||
|
||||
param set-default COM_DISARM_LAND 0.1
|
||||
param set-default COM_DISARM_PRFLT 3
|
||||
param set-default COM_FLTMODE1 -1
|
||||
param set-default COM_DL_LOSS_T 10
|
||||
param set-default COM_FLTMODE1 2
|
||||
param set-default COM_FLTMODE2 -1
|
||||
param set-default COM_FLTMODE3 -1
|
||||
param set-default COM_FLTMODE4 2
|
||||
param set-default COM_FLTMODE4 -1
|
||||
param set-default COM_FLTMODE5 -1
|
||||
param set-default COM_FLTMODE6 6
|
||||
param set-default COM_FLTMODE6 1
|
||||
param set-default COM_RC_LOSS_T 3
|
||||
|
||||
|
||||
@@ -146,7 +147,7 @@ param set-default MPC_Z_VEL_P 0.27
|
||||
# gimbal configuration
|
||||
param set-default MNT_MODE_IN 1
|
||||
param set-default MNT_MODE_OUT 1
|
||||
param set-default MNT_MAN_PITCH 1
|
||||
param set-default MNT_MAN_PITCH 2
|
||||
param set-default MNT_RC_IN_MODE 1
|
||||
param set-default MNT_RATE_PITCH 30
|
||||
|
||||
@@ -157,39 +158,10 @@ param set-default RC_MAP_THROTTLE 1
|
||||
param set-default RC_MAP_YAW 2
|
||||
param set-default RC_MAP_PITCH 3
|
||||
param set-default RC_MAP_ROLL 4
|
||||
param set-default RC_MAP_AUX1 5
|
||||
param set-default RC_MAP_FLTMODE 9
|
||||
|
||||
param set-default RC1_DZ 10
|
||||
param set-default RC1_MAX 4095
|
||||
param set-default RC1_MIN 0
|
||||
param set-default RC1_REV 1
|
||||
param set-default RC1_TRIM 0
|
||||
param set-default RC2_DZ 10
|
||||
param set-default RC2_MAX 4095
|
||||
param set-default RC2_MIN 0
|
||||
param set-default RC2_REV 1
|
||||
param set-default RC2_TRIM 2047
|
||||
param set-default RC3_DZ 10
|
||||
param set-default RC3_MAX 4095
|
||||
param set-default RC3_MIN 0
|
||||
param set-default RC3_REV 1
|
||||
param set-default RC3_TRIM 2047
|
||||
param set-default RC4_DZ 10
|
||||
param set-default RC4_MAX 4095
|
||||
param set-default RC4_MIN 0
|
||||
param set-default RC4_REV 1
|
||||
param set-default RC4_TRIM 2047
|
||||
param set-default RC5_DZ 10
|
||||
param set-default RC5_MAX 4095
|
||||
param set-default RC5_MIN 0
|
||||
param set-default RC5_REV 1
|
||||
param set-default RC5_TRIM 2047
|
||||
param set-default RC7_DZ 10
|
||||
param set-default RC7_MAX 4095
|
||||
param set-default RC7_MIN 0
|
||||
param set-default RC7_REV 1
|
||||
param set-default RC7_TRIM 2048
|
||||
param set-default RC_MAP_AUX2 5
|
||||
param set-default RC_MAP_AUX3 10
|
||||
param set-default RC_MAP_AUX4 8
|
||||
param set-default RC_MAP_FLTMODE 6
|
||||
|
||||
|
||||
# optical flow
|
||||
|
||||
Reference in New Issue
Block a user