mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
[WIP] explicit PWM configuration per channel
This commit is contained in:
@@ -11,6 +11,5 @@ param set-default NAV_DLL_ACT 0
|
||||
# disable circuit breaker for airspeed sensor
|
||||
param set-default CBRK_AIRSPD_CHK 162128
|
||||
|
||||
set PWM_OUT 12345678
|
||||
set MIXER_FILE etc/mixers-sitl/vectored6dof_sitl.main.mix
|
||||
set MIXER custom
|
||||
|
||||
@@ -12,4 +12,3 @@
|
||||
. ${R}etc/init.d/rc.airship_defaults
|
||||
|
||||
set MIXER cloudship
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -30,7 +30,6 @@ set MIXER_AUX none
|
||||
set MIXER_FILE none
|
||||
set OUTPUT_MODE sim
|
||||
set EXTRA_MIXER_MODE none
|
||||
set PWM_OUT none
|
||||
set SDCARD_MIXERS_PATH etc/mixers
|
||||
set USE_IO no
|
||||
set VEHICLE_TYPE none
|
||||
|
||||
@@ -23,8 +23,9 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
param set-default MC_ROLL_P 6.5
|
||||
param set-default MC_ROLLRATE_P 0.1
|
||||
@@ -38,6 +39,3 @@ param set-default MC_YAW_P 2.8
|
||||
param set-default MC_YAWRATE_P 0.28
|
||||
param set-default MC_YAWRATE_I 0.1
|
||||
param set-default MC_YAWRATE_D 0
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -21,8 +21,9 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
# TODO tune roll/pitch separately
|
||||
param set-default MC_ROLL_P 7
|
||||
@@ -40,6 +41,3 @@ param set-default MC_YAWRATE_D 0
|
||||
|
||||
param set-default BAT_V_DIV 12.27559
|
||||
param set-default BAT_A_PER_V 15.39103
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -23,8 +23,9 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
param set-default BAT_N_CELLS 4
|
||||
|
||||
@@ -40,6 +41,3 @@ param set-default MC_YAW_P 4
|
||||
param set-default MC_YAWRATE_P 0.2
|
||||
param set-default MC_YAWRATE_I 0.1
|
||||
param set-default MC_YAWRATE_D 0
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -23,8 +23,9 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
param set-default BAT_N_CELLS 6
|
||||
param set-default BAT_V_EMPTY 3.5
|
||||
@@ -43,8 +44,3 @@ param set-default MC_YAWRATE_I 0.1
|
||||
param set-default MC_YAWRATE_D 0
|
||||
|
||||
param set-default MPC_XY_VEL_MAX 2
|
||||
|
||||
param set-default PWM_MAIN_MIN 1080
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -11,7 +11,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set SYS_HITL 1
|
||||
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default BAT_N_CELLS 3
|
||||
|
||||
param set-default COM_RC_IN_MODE 1
|
||||
@@ -78,5 +77,3 @@ param set-default CBRK_IO_SAFETY 22027
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER standard_vtol_hitl
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -21,9 +21,6 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_hex_defaults
|
||||
|
||||
set MIXER hexa_cox
|
||||
|
||||
# Need to set all 8 channels
|
||||
set PWM_OUT 12345678
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
# set SYS_HITL to 2 to start the SIH and avoid sensors startup
|
||||
param set SYS_HITL 2
|
||||
|
||||
@@ -19,8 +19,7 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_octo_defaults
|
||||
|
||||
# MAIN set by rc.mc_octo_defaults
|
||||
set MIXER octo_cox
|
||||
|
||||
set PWM_OUT 12345678
|
||||
|
||||
@@ -20,8 +20,9 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.mc_octo_defaults
|
||||
|
||||
set MIXER octo_cox_w
|
||||
|
||||
param set-default MC_PITCH_P 4
|
||||
param set-default MC_PITCHRATE_P 0.24
|
||||
@@ -45,6 +46,3 @@ param set-default MPC_THR_MIN 0.15
|
||||
param set-default MPC_Z_VEL_MAX_DN 2
|
||||
|
||||
param set-default BAT_N_CELLS 4
|
||||
set MIXER octo_cox_w
|
||||
|
||||
set PWM_OUT 12345678
|
||||
|
||||
@@ -21,18 +21,21 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default VT_TYPE 2
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER quad_x
|
||||
# MAIN set by rc.mc_quad_defaults
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX vtol_AAERT
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 1500
|
||||
param set-default PWM_AUX_DIS4 1500
|
||||
param set-default PWM_AUX_DIS5 900 # throttle
|
||||
|
||||
@@ -18,8 +18,7 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default MAV_TYPE 19
|
||||
set MAV_TYPE 19
|
||||
|
||||
param set-default MC_ROLL_P 6
|
||||
param set-default MC_ROLLRATE_P 0.12
|
||||
@@ -43,8 +42,20 @@ param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_ELEV_MC_LOCK 0
|
||||
param set-default VT_MOT_ID 12
|
||||
param set-default VT_TYPE 0
|
||||
set MAV_TYPE 19
|
||||
|
||||
|
||||
# MAIN
|
||||
set MIXER vtol_tailsitter_duo
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
|
||||
set PWM_OUT 123456
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 1500 # right (starboard) elevon
|
||||
param set-default PWM_MAIN_DIS4 1500 # left (port) elevon.
|
||||
|
||||
@@ -23,6 +23,7 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 21
|
||||
|
||||
param set-default MC_ROLL_P 7
|
||||
param set-default MC_ROLLRATE_P 0.19
|
||||
@@ -40,8 +41,6 @@ param set-default MC_YAWRATE_I 0.02
|
||||
param set-default MC_YAWRATE_D 0
|
||||
param set-default MC_YAWRATE_FF 0
|
||||
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_FW_MOT_OFFID 34
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_MOT_ID 123456
|
||||
@@ -51,9 +50,40 @@ param set-default VT_TILT_TRANS 0.5
|
||||
param set-default VT_TILT_FW 0.9
|
||||
param set-default VT_ELEV_MC_LOCK 0
|
||||
param set-default VT_TYPE 1
|
||||
set MAV_TYPE 21
|
||||
|
||||
# MAIN
|
||||
set MIXER firefly6
|
||||
set MIXER_AUX firefly6
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1100
|
||||
param set-default PWM_MAIN_MIN5 1100
|
||||
param set-default PWM_MAIN_MIN6 1100
|
||||
|
||||
set PWM_OUT 12345678
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 1900
|
||||
param set-default PWM_MAIN_MAX5 1900
|
||||
param set-default PWM_MAIN_MAX6 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
param set-default PWM_MAIN_RATE4 400
|
||||
param set-default PWM_MAIN_RATE5 400
|
||||
param set-default PWM_MAIN_RATE6 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 900
|
||||
param set-default PWM_MAIN_DIS5 900
|
||||
param set-default PWM_MAIN_DIS6 900
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX firefly6
|
||||
param set-default PWM_MAIN_DIS1 1000 # Tilt mechanism servo mixer
|
||||
param set-default PWM_MAIN_DIS2 1500
|
||||
param set-default PWM_MAIN_DIS3 1500
|
||||
param set-default PWM_MAIN_DIS4 2000 # Landing gear
|
||||
|
||||
@@ -11,18 +11,18 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_MAIN_MAX 2000
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 0
|
||||
param set-default VT_ELEV_MC_LOCK 1
|
||||
set MAV_TYPE 20
|
||||
|
||||
set MIXER quad_x_vtol
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 0
|
||||
param set-default VT_ELEV_MC_LOCK 1
|
||||
|
||||
set PWM_OUT 1234
|
||||
# MAIN
|
||||
set MIXER quad_x_vtol
|
||||
# outputs 1-4 set by rc.mc_quad_defaults
|
||||
param set-default PWM_MAIN_DIS5 1500 # left elevon
|
||||
param set-default PWM_MAIN_DIS6 1500 # right elevon
|
||||
|
||||
@@ -20,17 +20,19 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_MAIN_MAX 2000
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 0
|
||||
param set-default VT_ELEV_MC_LOCK 1
|
||||
set MAV_TYPE 20
|
||||
|
||||
set MIXER quad_+_vtol
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 0
|
||||
param set-default VT_ELEV_MC_LOCK 1
|
||||
|
||||
set PWM_OUT 1234
|
||||
# MAIN
|
||||
set MIXER quad_+_vtol
|
||||
# outputs 1-4 set by rc.mc_quad_defaults
|
||||
param set-default PWM_MAIN_DIS5 1500
|
||||
param set-default PWM_MAIN_DIS6 1500
|
||||
param set-default PWM_MAIN_DIS7 1500
|
||||
param set-default PWM_MAIN_DIS8 1500
|
||||
|
||||
@@ -21,12 +21,10 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default MC_ROLL_P 6
|
||||
param set-default MC_ROLLRATE_P 0.17
|
||||
@@ -64,9 +62,14 @@ param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 2
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER quad_x
|
||||
|
||||
# MAIN set by rc.mc_quad_defaults
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX vtol_AAERT
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 1500
|
||||
param set-default PWM_AUX_DIS4 1500
|
||||
param set-default PWM_AUX_DIS5 900 # throttle
|
||||
|
||||
@@ -19,8 +19,10 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default MC_ROLL_P 6.5
|
||||
param set-default MC_ROLLRATE_P 0.15
|
||||
@@ -44,17 +46,17 @@ param set-default MPC_XY_VEL_P_ACC 2
|
||||
param set-default MPC_ACC_HOR_MAX 2
|
||||
param set-default MPC_YAWRAUTO_MAX 20
|
||||
|
||||
param set-default PWM_AUX_DIS3 950
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
param set-default VT_F_TRANS_THR 0.75
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 2
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER quad_x
|
||||
# MAIN set by rc.mc_quad_defaults
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX vtol_delta
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 900 # throttle
|
||||
param set-default PWM_AUX_DIS4 900 # throttle reverse
|
||||
|
||||
@@ -11,8 +11,10 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default MC_ROLL_P 7
|
||||
param set-default MC_ROLLRATE_P 0.15
|
||||
@@ -30,20 +32,20 @@ param set-default MC_YAWRATE_I 0.02
|
||||
param set-default MC_YAWRATE_D 0
|
||||
param set-default MC_YAWRATE_FF 0
|
||||
param set-default MC_YAWRATE_MAX 40
|
||||
|
||||
param set-default MPC_YAWRAUTO_MAX 40
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_F_TRANS_THR 0.75
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_TYPE 2
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER quad_x
|
||||
# MAIN set by rc.mc_quad_defaults
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX vtol_AAVVT
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 1500
|
||||
param set-default PWM_AUX_DIS4 1500
|
||||
param set-default PWM_AUX_DIS5 900 # throttle
|
||||
|
||||
@@ -11,8 +11,10 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default FW_THR_CRUISE 65
|
||||
param set-default FW_PR_P 0.08
|
||||
@@ -45,11 +47,6 @@ param set-default MPC_TKO_SPEED 1.5
|
||||
param set-default MPC_LAND_SPEED 0.8
|
||||
param set-default MPC_YAWRAUTO_MAX 40
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
param set-default PWM_AUX_REV1 1
|
||||
param set-default PWM_AUX_REV2 1
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_ARSP_TRANS 15
|
||||
param set-default VT_ARSP_BLEND 8
|
||||
param set-default VT_B_TRANS_DUR 4
|
||||
@@ -58,9 +55,13 @@ param set-default VT_IDLE_PWM_MC 1080
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
param set-default VT_TYPE 2
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER quad_x
|
||||
# MAIN set by rc.mc_quad_defaults
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX vtol_AAERT
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 1500
|
||||
param set-default PWM_AUX_DIS4 1500
|
||||
param set-default PWM_AUX_DIS5 900 # throttle
|
||||
|
||||
@@ -11,8 +11,10 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_quad_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default FW_AIRSPD_MAX 22
|
||||
param set-default FW_AIRSPD_MIN 14
|
||||
@@ -61,15 +63,6 @@ param set-default MPC_YAWRAUTO_MAX 40
|
||||
|
||||
param set-default NAV_ACC_RAD 3
|
||||
|
||||
param set-default PWM_AUX_REV1 1
|
||||
param set-default PWM_AUX_REV2 1
|
||||
param set-default PWM_AUX_REV3 1
|
||||
param set-default PWM_AUX_REV4 1
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default VT_ARSP_TRANS 15
|
||||
param set-default VT_B_TRANS_DUR 4
|
||||
param set-default VT_F_TRANS_THR 0.6
|
||||
@@ -80,9 +73,17 @@ param set-default VT_TRANS_MIN_TM 5
|
||||
param set-default VT_TRANS_TIMEOUT 30
|
||||
param set-default VT_TYPE 2
|
||||
|
||||
set MAV_TYPE 22
|
||||
# MAIN set by rc.mc_quad_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
# AUX
|
||||
set MIXER_AUX vtol_AAERT
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 1500
|
||||
param set-default PWM_AUX_DIS4 1500
|
||||
param set-default PWM_AUX_DIS5 900 # throttle
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_AUX_REV1 1
|
||||
param set-default PWM_AUX_REV2 1
|
||||
param set-default PWM_AUX_REV3 1
|
||||
param set-default PWM_AUX_REV4 1
|
||||
|
||||
@@ -13,14 +13,7 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DISARM 1000
|
||||
param set-default PWM_AUX_MAX 2000
|
||||
param set-default PWM_AUX_MIN 1000
|
||||
param set-default PWM_AUX_RATE 50
|
||||
|
||||
param set-default PWM_MAIN_MAX 2000
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
set MAV_TYPE 21
|
||||
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 13
|
||||
@@ -30,9 +23,32 @@ param set-default VT_TILT_MC 0.08
|
||||
param set-default VT_TILT_TRANS 0.5
|
||||
param set-default VT_ELEV_MC_LOCK 0
|
||||
param set-default VT_TYPE 1
|
||||
set MAV_TYPE 21
|
||||
|
||||
set MIXER claire
|
||||
|
||||
# MAIN
|
||||
set MIXER quad_x
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1100
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
param set-default PWM_MAIN_RATE4 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 900
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX claire
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_MAIN_DIS1 1000 # tilt
|
||||
param set-default PWM_MAIN_DIS2 1500 # elevon
|
||||
param set-default PWM_MAIN_DIS3 1500 # elevon
|
||||
|
||||
@@ -22,6 +22,7 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 21
|
||||
|
||||
param set-default CBRK_AIRSPD_CHK 162128
|
||||
|
||||
@@ -59,8 +60,6 @@ param set-default MPC_LAND_SPEED 1.2
|
||||
param set-default MPC_TKO_SPEED 2.5
|
||||
param set-default MPC_Z_VEL_MAX_UP 3
|
||||
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default SENS_BOARD_ROT 8
|
||||
|
||||
param set-default VT_B_TRANS_DUR 1
|
||||
@@ -79,8 +78,26 @@ param set-default VT_TRANS_MIN_TM 1.2
|
||||
param set-default VT_TRANS_P2_DUR 1.3
|
||||
param set-default VT_ELEV_MC_LOCK 0
|
||||
param set-default VT_TYPE 1
|
||||
set MAV_TYPE 21
|
||||
|
||||
|
||||
# MAIN
|
||||
set MIXER vtol_convergence
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS5 2000 # tilt right servo (2000 up)
|
||||
param set-default PWM_MAIN_DIS6 1000 # tilt left servo (1000 up)
|
||||
param set-default PWM_MAIN_DIS7 1500 # elevon
|
||||
param set-default PWM_MAIN_DIS8 1500 # elevon
|
||||
|
||||
@@ -22,6 +22,7 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default BAT_CAPACITY 23000
|
||||
param set-default BAT_N_CELLS 4
|
||||
@@ -112,15 +113,6 @@ param set-default MPC_YAWRAUTO_MAX 20
|
||||
param set-default NAV_DLL_ACT 0
|
||||
param set-default NAV_LOITER_RAD 100
|
||||
|
||||
param set-default PWM_AUX_DISARM 950
|
||||
|
||||
param set-default PWM_MAIN_DIS5 1500
|
||||
param set-default PWM_MAIN_DIS6 1500
|
||||
param set-default PWM_MAIN_DIS7 900
|
||||
param set-default PWM_MAIN_DIS8 900
|
||||
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default SENS_BOARD_ROT 18
|
||||
|
||||
# TELEM2 config
|
||||
@@ -150,10 +142,34 @@ param set-default VT_TRANS_TIMEOUT 22
|
||||
param set-default VT_F_TRANS_RAMP 4
|
||||
|
||||
param set-default COM_RC_OVERRIDE 0
|
||||
set MAV_TYPE 22
|
||||
|
||||
|
||||
# MAIN
|
||||
set MIXER deltaquad
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1100
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
param set-default PWM_MAIN_RATE4 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 900
|
||||
param set-default PWM_MAIN_DIS5 1500 # left elevon
|
||||
param set-default PWM_MAIN_DIS6 1500 # right elevon
|
||||
param set-default PWM_MAIN_DIS7 900 # pusher
|
||||
param set-default PWM_MAIN_DIS8 900 # reverse thrust
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX pass
|
||||
|
||||
set PWM_OUT 1234
|
||||
set PWM_AUX_OUT 12345
|
||||
|
||||
@@ -22,7 +22,7 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default BAT_N_CELLS 6
|
||||
|
||||
@@ -105,11 +105,28 @@ param set-default VT_PSHER_RMP_DT 2
|
||||
param set-default VT_TRANS_MIN_TM 4
|
||||
param set-default VT_TYPE 2
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
# MAIN
|
||||
set MIXER babyshark
|
||||
set MIXER_AUX pass
|
||||
param set-default PWM_MAIN_MIN5 1100
|
||||
param set-default PWM_MAIN_MIN6 1100
|
||||
param set-default PWM_MAIN_MIN7 1120
|
||||
param set-default PWM_MAIN_MIN8 1100
|
||||
|
||||
# Mark outputs for the alternate rate
|
||||
# or D-Shot
|
||||
set PWM_OUT 5678
|
||||
param set-default PWM_MAIN_MAX5 1900
|
||||
param set-default PWM_MAIN_MAX6 1900
|
||||
param set-default PWM_MAIN_MAX7 1900
|
||||
param set-default PWM_MAIN_MAX8 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE5 400
|
||||
param set-default PWM_MAIN_RATE6 400
|
||||
param set-default PWM_MAIN_RATE7 400
|
||||
param set-default PWM_MAIN_RATE8 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 1500
|
||||
param set-default PWM_MAIN_DIS2 1500
|
||||
param set-default PWM_MAIN_DIS3 900 # pusher
|
||||
param set-default PWM_MAIN_DIS4 1500
|
||||
param set-default PWM_MAIN_DIS5 900
|
||||
param set-default PWM_MAIN_DIS6 900
|
||||
param set-default PWM_MAIN_DIS7 900
|
||||
param set-default PWM_MAIN_DIS8 900
|
||||
|
||||
@@ -0,0 +1,53 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Generic Quadplane VTOL (PWM14)
|
||||
#
|
||||
# @type Standard VTOL
|
||||
# @class VTOL
|
||||
#
|
||||
# @maintainer
|
||||
#
|
||||
# @output MAIN1 motor 1
|
||||
# @output MAIN2 motor 2
|
||||
# @output MAIN3 motor 3
|
||||
# @output MAIN4 motor 4
|
||||
# @output MAIN5 Aileron 1
|
||||
# @output MAIN6 Aileron 2
|
||||
# @output MAIN7 Elevator
|
||||
# @output MAIN8 Rudder
|
||||
# @output MAIN9 Pusher motor
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
# @board intel_aerofc-v1 exclude
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default VT_TYPE 2
|
||||
param set-default VT_MOT_ID 1234
|
||||
param set-default VT_FW_MOT_OFFID 1234
|
||||
|
||||
# MAIN
|
||||
set MIXER quad_x_vtol_AAERT
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1100
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 1900
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 900
|
||||
param set-default PWM_MAIN_DIS5 1500
|
||||
param set-default PWM_MAIN_DIS6 1500
|
||||
param set-default PWM_MAIN_DIS7 1500
|
||||
param set-default PWM_MAIN_DIS8 1500
|
||||
param set-default PWM_MAIN_DIS9 900
|
||||
@@ -23,18 +23,21 @@
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_octo_defaults
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
set MAV_TYPE 22
|
||||
|
||||
param set-default VT_TYPE 2
|
||||
param set-default VT_MOT_ID 12345678
|
||||
param set-default VT_FW_MOT_OFFID 12345678
|
||||
set MAV_TYPE 22
|
||||
|
||||
set MIXER octo_cox
|
||||
# MAIN set by rc.mc_octo_defaults
|
||||
|
||||
# AUX
|
||||
set MIXER_AUX vtol_AAERT
|
||||
|
||||
set PWM_OUT 12345678
|
||||
param set-default PWM_AUX_DIS1 1500
|
||||
param set-default PWM_AUX_DIS2 1500
|
||||
param set-default PWM_AUX_DIS3 1500
|
||||
param set-default PWM_AUX_DIS4 1500
|
||||
param set-default PWM_AUX_DIS5 900 # throttle
|
||||
|
||||
@@ -18,13 +18,26 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default VT_ELEV_MC_LOCK 0
|
||||
param set-default VT_MOT_COUNT 2
|
||||
param set-default VT_TYPE 0
|
||||
|
||||
param set-default MAV_TYPE 19
|
||||
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS5 1500 # right elevon
|
||||
param set-default PWM_MAIN_DIS6 1500 # left elevon
|
||||
|
||||
|
||||
set MAV_TYPE 19
|
||||
set MIXER vtol_tailsitter_duo
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -19,4 +19,22 @@
|
||||
|
||||
set MIXER tri_y_yaw+
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1000
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 2000
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
param set-default PWM_MAIN_RATE4 50
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 1500
|
||||
|
||||
@@ -19,4 +19,22 @@
|
||||
|
||||
set MIXER tri_y_yaw-
|
||||
|
||||
set PWM_OUT 1234
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1000
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 2000
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
param set-default PWM_MAIN_RATE4 50
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 1500
|
||||
|
||||
@@ -17,8 +17,8 @@
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
set MIXER coax
|
||||
|
||||
set MIXER coax
|
||||
|
||||
param set-default MC_ROLL_P 6.5
|
||||
param set-default MC_ROLLRATE_P 0.17
|
||||
@@ -38,17 +38,5 @@ param set-default MC_YAWRATE_FF 0
|
||||
|
||||
param set-default NAV_ACC_RAD 2
|
||||
|
||||
param set-default PWM_AUX_RATE 50
|
||||
param set-default PWM_MAIN_DISARM 900
|
||||
param set-default PWM_MAIN_MIN 1075
|
||||
param set-default PWM_MAIN_MAX 1950
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default RTL_RETURN_ALT 30
|
||||
param set-default RTL_DESCEND_ALT 10
|
||||
# This is the gimbal pass mixer
|
||||
set MIXER_AUX pass
|
||||
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_AUX_OUT 1234
|
||||
set PWM_OUT 34
|
||||
|
||||
@@ -24,11 +24,6 @@ set MAV_TYPE 4
|
||||
|
||||
set MIXER blade130
|
||||
|
||||
#set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default ATT_BIAS_MAX 0
|
||||
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
|
||||
param set-default MC_ROLL_P 5
|
||||
@@ -53,5 +48,3 @@ param set-default MC_ACRO_P_MAX 360
|
||||
|
||||
param set-default MPC_THR_MIN 0.06
|
||||
param set-default MPC_MANTHR_MIN 0.06
|
||||
|
||||
param set-default PWM_MAIN_MIN 1075
|
||||
|
||||
@@ -25,13 +25,9 @@
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
|
||||
param set-default BAT_CAPACITY 2500
|
||||
param set-default BAT_N_CELLS 3
|
||||
|
||||
param set-default PWM_AUX_RATE 50
|
||||
param set-default PWM_MAIN_RATE 50
|
||||
|
||||
param set-default SENS_BOARD_ROT 8
|
||||
|
||||
param set-default FW_AIRSPD_MAX 20
|
||||
@@ -46,5 +42,6 @@ param set-default FW_R_LIM 40
|
||||
param set-default FW_P_LIM_MAX 25
|
||||
param set-default FW_P_LIM_MIN -5
|
||||
param set-default FW_P_RMAX_NEG 20
|
||||
|
||||
set MIXER TF-AutoG2
|
||||
set MIXER_AUX pass
|
||||
|
||||
@@ -20,13 +20,9 @@
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
|
||||
param set-default BAT_CAPACITY 3300
|
||||
param set-default BAT_N_CELLS 3
|
||||
|
||||
param set-default PWM_AUX_RATE 50
|
||||
param set-default PWM_MAIN_RATE 50
|
||||
|
||||
param set-default SENS_BOARD_ROT 4
|
||||
|
||||
param set-default FW_AIRSPD_MAX 20
|
||||
@@ -41,5 +37,6 @@ param set-default FW_R_LIM 40
|
||||
param set-default FW_P_LIM_MAX 25
|
||||
param set-default FW_P_LIM_MIN -5
|
||||
param set-default FW_P_RMAX_NEG 20
|
||||
|
||||
set MIXER TF-G2
|
||||
set MIXER_AUX pass
|
||||
|
||||
@@ -15,7 +15,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.balloon_defaults
|
||||
|
||||
|
||||
param set-default COM_PREARM_MODE 2 # always in prearm state
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
param set-default SDLOG_PROFILE 17
|
||||
@@ -26,8 +25,8 @@ param set-default GPS_UBX_DYNMODEL 8
|
||||
param set-default SER_TEL2_BAUD 9600
|
||||
|
||||
param set-default SENS_BOARD_ROT 0
|
||||
param set MAV_TYPE 8 # MAV_TYPE_FREE_BALLOON
|
||||
|
||||
param set-default MAV_TYPE 8 # MAV_TYPE_FREE_BALLOON
|
||||
|
||||
set MIXER IO_pass
|
||||
set MIXER_AUX pass
|
||||
|
||||
@@ -23,10 +23,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
param set-default PWM_AUX_RATE 50
|
||||
param set-default PWM_MAIN_RATE 50
|
||||
|
||||
set MIXER AETRFG
|
||||
|
||||
# Rate must be set by group (see pwm info).
|
||||
# Throttle is in the same group as servos.
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
|
||||
@@ -39,11 +39,7 @@ param set-default FW_WR_IMAX 0.8
|
||||
param set-default FW_WR_P 1
|
||||
param set-default FW_W_RMAX 0
|
||||
|
||||
# set disarmed value for the ESC
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
|
||||
set MIXER AAERTWF
|
||||
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_OUT 5
|
||||
param set-default PWM_MAIN_DIS5 1000
|
||||
|
||||
@@ -39,11 +39,7 @@ param set-default FW_WR_IMAX 0.8
|
||||
param set-default FW_WR_P 1
|
||||
param set-default FW_W_RMAX 0
|
||||
|
||||
# set disarmed value for the ESC
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
|
||||
set MIXER AAVVTWFF
|
||||
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_OUT 5
|
||||
param set-default PWM_MAIN_DIS5 1000
|
||||
|
||||
@@ -40,13 +40,10 @@ param set-default FW_WR_IMAX 0.8
|
||||
param set-default FW_WR_P 1
|
||||
param set-default FW_W_RMAX 0
|
||||
|
||||
# set disarmed value for the ESC
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
# The Mini Talon does not have a wheel and
|
||||
# no flaps. I leave them here because the mixer
|
||||
# computes also wheel and flap controls.
|
||||
set MIXER AAVVTWFF_vtail
|
||||
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_OUT 5
|
||||
param set-default PWM_MAIN_DIS5 1000
|
||||
|
||||
@@ -27,23 +27,68 @@
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
|
||||
param set-default NAV_ACC_RAD 2
|
||||
|
||||
param set-default PWM_AUX_RATE 400
|
||||
param set-default PWM_AUX_DISARM 900
|
||||
param set-default PWM_AUX_MIN 1075
|
||||
param set-default PWM_AUX_MAX 1950
|
||||
|
||||
param set-default PWM_MAIN_MIN 1075
|
||||
param set-default PWM_MAIN_MAX 1950
|
||||
param set-default PWM_MAIN_RATE 400
|
||||
|
||||
param set-default RTL_DESCEND_ALT 10
|
||||
param set-default RTL_RETURN_ALT 30
|
||||
|
||||
# MAIN
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1100
|
||||
param set-default PWM_MAIN_MIN5 1100
|
||||
param set-default PWM_MAIN_MIN6 1100
|
||||
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 1900
|
||||
param set-default PWM_MAIN_MAX5 1900
|
||||
param set-default PWM_MAIN_MAX6 1900
|
||||
|
||||
param set-default PWM_MAIN_RATE1 400
|
||||
param set-default PWM_MAIN_RATE2 400
|
||||
param set-default PWM_MAIN_RATE3 400
|
||||
param set-default PWM_MAIN_RATE4 400
|
||||
param set-default PWM_MAIN_RATE5 400
|
||||
param set-default PWM_MAIN_RATE6 400
|
||||
|
||||
param set-default PWM_MAIN_DIS1 900
|
||||
param set-default PWM_MAIN_DIS2 900
|
||||
param set-default PWM_MAIN_DIS3 900
|
||||
param set-default PWM_MAIN_DIS4 900
|
||||
param set-default PWM_MAIN_DIS5 900
|
||||
param set-default PWM_MAIN_DIS6 900
|
||||
|
||||
# AUX
|
||||
param set-default PWM_AUX_MIN1 1100
|
||||
param set-default PWM_AUX_MIN2 1100
|
||||
param set-default PWM_AUX_MIN3 1100
|
||||
param set-default PWM_AUX_MIN4 1100
|
||||
param set-default PWM_AUX_MIN5 1100
|
||||
param set-default PWM_AUX_MIN6 1100
|
||||
|
||||
param set-default PWM_AUX_MAX1 1900
|
||||
param set-default PWM_AUX_MAX2 1900
|
||||
param set-default PWM_AUX_MAX3 1900
|
||||
param set-default PWM_AUX_MAX4 1900
|
||||
param set-default PWM_AUX_MAX5 1900
|
||||
param set-default PWM_AUX_MAX6 1900
|
||||
|
||||
param set-default PWM_AUX_RATE1 400
|
||||
param set-default PWM_AUX_RATE2 400
|
||||
param set-default PWM_AUX_RATE3 400
|
||||
param set-default PWM_AUX_RATE4 400
|
||||
param set-default PWM_AUX_RATE5 400
|
||||
param set-default PWM_AUX_RATE6 400
|
||||
|
||||
param set-default PWM_AUX_DIS1 900
|
||||
param set-default PWM_AUX_DIS2 900
|
||||
param set-default PWM_AUX_DIS3 900
|
||||
param set-default PWM_AUX_DIS4 900
|
||||
param set-default PWM_AUX_DIS5 900
|
||||
param set-default PWM_AUX_DIS6 900
|
||||
|
||||
set MIXER dodeca_top_cox
|
||||
set MIXER_AUX dodeca_bottom_cox
|
||||
|
||||
# Need to set all 8 channels
|
||||
set PWM_OUT 12345678
|
||||
set PWM_AUX_OUT 123456
|
||||
|
||||
@@ -18,6 +18,4 @@
|
||||
param set-default COM_PREARM_MODE 2
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
|
||||
|
||||
set MIXER cloudship
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -21,3 +21,5 @@
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER fw_generic_wing
|
||||
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
@@ -9,10 +9,6 @@
|
||||
# @output MAIN2 right aileron
|
||||
# @output MAIN4 throttle
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
# @output AUX2 feed-through of RC AUX2 channel
|
||||
# @output AUX3 feed-through of RC AUX3 channel
|
||||
#
|
||||
# @maintainer Simon Wilks <simon@uaventure.com>
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
@@ -41,10 +37,8 @@ param set-default FW_RR_FF 0.6
|
||||
param set-default FW_RR_IMAX 0.2
|
||||
param set-default FW_RR_P 0.04
|
||||
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
|
||||
set MIXER fw_generic_wing
|
||||
|
||||
# Provide ESC a constant 1000 us pulse while disarmed
|
||||
set PWM_OUT 4
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
@@ -11,10 +11,6 @@
|
||||
# @output MAIN2 right aileron
|
||||
# @output MAIN4 throttle
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
# @output AUX2 feed-through of RC AUX2 channel
|
||||
# @output AUX3 feed-through of RC AUX3 channel
|
||||
#
|
||||
# @maintainer Simon Wilks <simon@uaventure.com>
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
@@ -42,8 +38,6 @@ param set-default FW_RR_P 0.08
|
||||
param set-default FW_R_LIM 50
|
||||
param set-default FW_R_RMAX 50
|
||||
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
# Bottom of bay and nominal zero-pitch attitude differ
|
||||
# the payload bay is pitched up about 7 degrees
|
||||
param set-default SENS_BOARD_Y_OFF 7
|
||||
@@ -51,5 +45,5 @@ param set-default SENS_BOARD_Y_OFF 7
|
||||
|
||||
set MIXER phantom
|
||||
|
||||
# Provide ESC a constant 1000 us pulse
|
||||
set PWM_OUT 4
|
||||
# Provide ESC a constant 1000 us pulse while disarmed
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
@@ -41,8 +41,6 @@ param set-default FW_PR_FF 0.35
|
||||
param set-default FW_RR_FF 0.6
|
||||
param set-default FW_RR_P 0.04
|
||||
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
|
||||
# Configure this as plane.
|
||||
set MAV_TYPE 1
|
||||
@@ -50,5 +48,5 @@ set MAV_TYPE 1
|
||||
# Set mixer.
|
||||
set MIXER wingwing
|
||||
|
||||
# Provide ESC a constant 1000 us pulse.
|
||||
set PWM_OUT 4
|
||||
# Provide ESC a constant 1000 us pulse while disarmed
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
@@ -27,5 +27,6 @@ param set-default FW_AIRSPD_TRIM 15
|
||||
|
||||
param set-default NAV_LOITER_RAD 150
|
||||
|
||||
|
||||
set MIXER FX79
|
||||
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
@@ -21,3 +21,5 @@
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER Viper
|
||||
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
@@ -43,14 +43,10 @@ param set-default FW_R_LIM 40
|
||||
param set-default FW_R_RMAX 50
|
||||
param set-default FW_R_TC 0.3
|
||||
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
param set-default PWM_MAIN_DIS4 1000
|
||||
|
||||
# Bottom of bay and nominal zero-pitch attitude differ
|
||||
# the payload bay is pitched up about 7 degrees
|
||||
param set-default SENS_BOARD_Y_OFF 11.9
|
||||
|
||||
|
||||
set MIXER phantom
|
||||
|
||||
# Provide ESC a constant 1000 us pulse
|
||||
set PWM_OUT 4
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user