forked from Archive/PX4-Autopilot
ROMFS: set control allocation parameters for sitl airframes
Removes some airframes: - if750a - solo - iris_ctrlalloc - typhoon_h480_ctrlalloc
This commit is contained in:
parent
f2db7b8deb
commit
4d60fadc05
|
@ -35,6 +35,5 @@ add_subdirectory(init.d)
|
||||||
add_subdirectory(mixers)
|
add_subdirectory(mixers)
|
||||||
# TODO: make this configurable from the board config, or better combine
|
# TODO: make this configurable from the board config, or better combine
|
||||||
if("${PX4_BOARD}" MATCHES "sitl")
|
if("${PX4_BOARD}" MATCHES "sitl")
|
||||||
add_subdirectory(mixers-sitl)
|
|
||||||
add_subdirectory(init.d-posix)
|
add_subdirectory(init.d-posix)
|
||||||
endif()
|
endif()
|
||||||
|
|
|
@ -9,4 +9,25 @@
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
. ${R}etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER quad_w
|
|
||||||
|
param set-default CA_AIRFRAME 0
|
||||||
|
|
||||||
|
param set-default CA_ROTOR_COUNT 4
|
||||||
|
param set-default CA_ROTOR0_PX 0.1515
|
||||||
|
param set-default CA_ROTOR0_PY 0.245
|
||||||
|
param set-default CA_ROTOR0_KM 0.05
|
||||||
|
param set-default CA_ROTOR1_PX -0.1515
|
||||||
|
param set-default CA_ROTOR1_PY -0.1875
|
||||||
|
param set-default CA_ROTOR1_KM 0.05
|
||||||
|
param set-default CA_ROTOR2_PX 0.1515
|
||||||
|
param set-default CA_ROTOR2_PY -0.245
|
||||||
|
param set-default CA_ROTOR2_KM -0.05
|
||||||
|
param set-default CA_ROTOR3_PX -0.1515
|
||||||
|
param set-default CA_ROTOR3_PY 0.1875
|
||||||
|
param set-default CA_ROTOR3_KM -0.05
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
|
||||||
|
|
|
@ -1,35 +0,0 @@
|
||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# @name 3DR Iris Quadrotor SITL
|
|
||||||
#
|
|
||||||
# @type Quadrotor Wide
|
|
||||||
#
|
|
||||||
# @maintainer Julian Oes <julian@oes.ch>
|
|
||||||
#
|
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
|
||||||
|
|
||||||
|
|
||||||
param set-default CA_AIRFRAME 0
|
|
||||||
|
|
||||||
param set-default CA_ROTOR_COUNT 4
|
|
||||||
param set-default CA_ROTOR0_PX 0.1515
|
|
||||||
param set-default CA_ROTOR0_PY 0.245
|
|
||||||
param set-default CA_ROTOR0_KM 0.05
|
|
||||||
param set-default CA_ROTOR1_PX -0.1515
|
|
||||||
param set-default CA_ROTOR1_PY -0.1875
|
|
||||||
param set-default CA_ROTOR1_KM 0.05
|
|
||||||
param set-default CA_ROTOR2_PX 0.1515
|
|
||||||
param set-default CA_ROTOR2_PY -0.245
|
|
||||||
param set-default CA_ROTOR2_KM -0.05
|
|
||||||
param set-default CA_ROTOR3_PX -0.1515
|
|
||||||
param set-default CA_ROTOR3_PY 0.1875
|
|
||||||
param set-default CA_ROTOR3_KM -0.05
|
|
||||||
|
|
||||||
param set-default PWM_MAIN_FUNC1 101
|
|
||||||
param set-default PWM_MAIN_FUNC2 102
|
|
||||||
param set-default PWM_MAIN_FUNC3 103
|
|
||||||
param set-default PWM_MAIN_FUNC4 104
|
|
||||||
|
|
||||||
set MIXER skip
|
|
||||||
set MIXER_AUX none
|
|
|
@ -95,5 +95,3 @@ param set-default CA_METHOD 0
|
||||||
param set-default FD_FAIL_P 0
|
param set-default FD_FAIL_P 0
|
||||||
param set-default FD_FAIL_R 0
|
param set-default FD_FAIL_R 0
|
||||||
|
|
||||||
set MIXER skip
|
|
||||||
set MIXER_AUX none
|
|
||||||
|
|
|
@ -1,19 +0,0 @@
|
||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# @name IF750A SITL
|
|
||||||
# InspiredFlight 750 Auterion edition. Gazebo Only.
|
|
||||||
#
|
|
||||||
# @type Quadrotor
|
|
||||||
#
|
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
|
||||||
|
|
||||||
# EKF2: Multi GPS blending (as the model has 2 GPS's)
|
|
||||||
param set-default SENS_GPS_MASK 7
|
|
||||||
param set-default TRIG_INTERFACE 3
|
|
||||||
param set-default TRIG_MODE 4
|
|
||||||
param set-default MNT_MODE_IN 4
|
|
||||||
param set-default MNT_MODE_OUT 2
|
|
||||||
param set-default MNT_DO_STAB 2
|
|
||||||
|
|
||||||
set MIXER quad_x
|
|
|
@ -8,4 +8,8 @@
|
||||||
|
|
||||||
. ${R}etc/init.d/airframes/4016_holybro_px4vision
|
. ${R}etc/init.d/airframes/4016_holybro_px4vision
|
||||||
|
|
||||||
set MIXER quad_x
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
|
||||||
|
|
|
@ -9,7 +9,6 @@
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
. ${R}etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER quad_x
|
|
||||||
|
|
||||||
# disable some checks to allow to fly:
|
# disable some checks to allow to fly:
|
||||||
# - with usb
|
# - with usb
|
||||||
|
@ -20,4 +19,24 @@ param set-default CBRK_SUPPLY_CHK 894281
|
||||||
param set-default COM_PREARM_MODE 0
|
param set-default COM_PREARM_MODE 0
|
||||||
param set-default CBRK_IO_SAFETY 22027
|
param set-default CBRK_IO_SAFETY 22027
|
||||||
|
|
||||||
|
param set-default CA_ROTOR_COUNT 4
|
||||||
|
param set-default CA_ROTOR0_PX 0.15
|
||||||
|
param set-default CA_ROTOR0_PY 0.15
|
||||||
|
param set-default CA_ROTOR0_KM 0.05
|
||||||
|
param set-default CA_ROTOR1_PX -0.15
|
||||||
|
param set-default CA_ROTOR1_PY -0.15
|
||||||
|
param set-default CA_ROTOR1_KM 0.05
|
||||||
|
param set-default CA_ROTOR2_PX 0.15
|
||||||
|
param set-default CA_ROTOR2_PY -0.15
|
||||||
|
param set-default CA_ROTOR2_KM -0.05
|
||||||
|
param set-default CA_ROTOR3_PX -0.15
|
||||||
|
param set-default CA_ROTOR3_PY 0.15
|
||||||
|
param set-default CA_ROTOR3_KM -0.05
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
|
||||||
param set SIH_VEHICLE_TYPE 0
|
param set SIH_VEHICLE_TYPE 0
|
||||||
|
|
||||||
|
|
|
@ -8,7 +8,6 @@
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.fw_defaults
|
. ${R}etc/init.d/rc.fw_defaults
|
||||||
|
|
||||||
set MIXER AERT
|
|
||||||
|
|
||||||
# disable some checks to allow to fly:
|
# disable some checks to allow to fly:
|
||||||
# - with usb
|
# - with usb
|
||||||
|
@ -21,13 +20,30 @@ param set-default CBRK_IO_SAFETY 22027
|
||||||
|
|
||||||
param set-default BAT_N_CELLS 3
|
param set-default BAT_N_CELLS 3
|
||||||
|
|
||||||
param set SIH_T_MAX 6.0
|
param set-default SIH_T_MAX 6.0
|
||||||
param set SIH_MASS 0.3
|
param set-default SIH_MASS 0.3
|
||||||
param set SIH_IXX 0.00402
|
param set-default SIH_IXX 0.00402
|
||||||
param set SIH_IYY 0.0144
|
param set-default SIH_IYY 0.0144
|
||||||
param set SIH_IZZ 0.0177
|
param set-default SIH_IZZ 0.0177
|
||||||
param set SIH_IXZ 0.00046
|
param set-default SIH_IXZ 0.00046
|
||||||
param set SIH_KDV 0.2
|
param set-default SIH_KDV 0.2
|
||||||
|
|
||||||
param set SIH_VEHICLE_TYPE 1 # sih as fixed wing
|
param set-default SIH_VEHICLE_TYPE 1 # sih as fixed wing
|
||||||
param set RWTO_TKOFF 1 # enable takeoff from runway (as opposed to launched)
|
param set-default RWTO_TKOFF 1 # enable takeoff from runway (as opposed to launched)
|
||||||
|
|
||||||
|
|
||||||
|
param set-default CA_AIRFRAME 1
|
||||||
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 3
|
||||||
|
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS0_TYPE 1
|
||||||
|
param set-default CA_SV_CS1_TRQ_P 1.0
|
||||||
|
param set-default CA_SV_CS1_TYPE 3
|
||||||
|
param set-default CA_SV_CS2_TRQ_Y 1.0
|
||||||
|
param set-default CA_SV_CS2_TYPE 4
|
||||||
|
param set-default PWM_MAIN_FUNC3 201
|
||||||
|
param set-default PWM_MAIN_FUNC4 202
|
||||||
|
param set-default PWM_MAIN_FUNC5 203
|
||||||
|
param set-default PWM_MAIN_FUNC6 101
|
||||||
|
|
|
@ -16,8 +16,6 @@ param set-default MPC_MAN_Y_MAX 60
|
||||||
param set-default MC_PITCH_P 5
|
param set-default MC_PITCH_P 5
|
||||||
|
|
||||||
param set-default MAV_TYPE 19
|
param set-default MAV_TYPE 19
|
||||||
set MAV_TYPE 19
|
|
||||||
set MIXER vtol_tailsitter_duo_sat
|
|
||||||
|
|
||||||
# disable some checks to allow to fly:
|
# disable some checks to allow to fly:
|
||||||
# - with usb
|
# - with usb
|
||||||
|
@ -30,16 +28,39 @@ param set-default CBRK_IO_SAFETY 22027
|
||||||
|
|
||||||
param set-default BAT_N_CELLS 3
|
param set-default BAT_N_CELLS 3
|
||||||
|
|
||||||
param set SIH_T_MAX 2.0
|
param set-default SIH_T_MAX 2.0
|
||||||
param set SIH_Q_MAX 0.0165
|
param set-default SIH_Q_MAX 0.0165
|
||||||
param set SIH_MASS 0.2
|
param set-default SIH_MASS 0.2
|
||||||
# IXX and IZZ are inverted from the thesis as the body frame is pitched by 90 deg
|
# IXX and IZZ are inverted from the thesis as the body frame is pitched by 90 deg
|
||||||
param set SIH_IXX 0.00354
|
param set-default SIH_IXX 0.00354
|
||||||
param set SIH_IYY 0.000625
|
param set-default SIH_IYY 0.000625
|
||||||
param set SIH_IZZ 0.00300
|
param set-default SIH_IZZ 0.00300
|
||||||
param set SIH_IXZ 0.0
|
param set-default SIH_IXZ 0.0
|
||||||
param set SIH_KDV 0.2
|
param set-default SIH_KDV 0.2
|
||||||
param set SIH_L_ROLL 0.145
|
param set-default SIH_L_ROLL 0.145
|
||||||
|
|
||||||
# sih as tailsitter
|
# sih as tailsitter
|
||||||
param set SIH_VEHICLE_TYPE 2
|
param set-default SIH_VEHICLE_TYPE 2
|
||||||
|
|
||||||
|
param set-default CA_AIRFRAME 4
|
||||||
|
|
||||||
|
param set-default CA_ROTOR_COUNT 2
|
||||||
|
param set-default CA_ROTOR0_PX 0
|
||||||
|
param set-default CA_ROTOR0_PY 2
|
||||||
|
param set-default CA_ROTOR0_KM 0.05
|
||||||
|
param set-default CA_ROTOR1_PX 0
|
||||||
|
param set-default CA_ROTOR1_PY -1
|
||||||
|
param set-default CA_ROTOR1_KM 0.05
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 2
|
||||||
|
param set-default CA_SV_CS0_TYPE 5
|
||||||
|
param set-default CA_SV_CS0_TRQ_P 0.5
|
||||||
|
param set-default CA_SV_CS0_TRQ_Y -0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 6
|
||||||
|
param set-default CA_SV_CS1_TRQ_P 0.5
|
||||||
|
param set-default CA_SV_CS1_TRQ_Y 0.5
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC5 201
|
||||||
|
param set-default PWM_MAIN_FUNC6 202
|
||||||
|
|
|
@ -1,13 +0,0 @@
|
||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# @name Solo
|
|
||||||
#
|
|
||||||
# @type Quadrotor
|
|
||||||
#
|
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
|
||||||
|
|
||||||
param set-default MC_PITCHRATE_P 0.1
|
|
||||||
param set-default MC_ROLLRATE_P 0.05
|
|
||||||
|
|
||||||
set MIXER quad_x
|
|
|
@ -1,12 +0,0 @@
|
||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# @name UUV
|
|
||||||
#
|
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.uuv_defaults
|
|
||||||
|
|
||||||
# disable circuit breaker for airspeed sensor
|
|
||||||
param set-default CBRK_AIRSPD_CHK 162128
|
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix
|
|
||||||
set MIXER custom
|
|
|
@ -8,5 +8,40 @@
|
||||||
# disable circuit breaker for airspeed sensor
|
# disable circuit breaker for airspeed sensor
|
||||||
param set-default CBRK_AIRSPD_CHK 162128
|
param set-default CBRK_AIRSPD_CHK 162128
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix
|
param set-default CA_AIRFRAME 7
|
||||||
set MIXER custom
|
param set-default CA_ROTOR_COUNT 4
|
||||||
|
param set-default CA_R_REV 255
|
||||||
|
param set-default CA_ROTOR0_AX 1.0000
|
||||||
|
param set-default CA_ROTOR0_AY 0.0000
|
||||||
|
param set-default CA_ROTOR0_AZ 0.0000
|
||||||
|
param set-default CA_ROTOR0_KM 0.0000
|
||||||
|
param set-default CA_ROTOR0_PX 0.0000
|
||||||
|
param set-default CA_ROTOR0_PY -0.3000
|
||||||
|
param set-default CA_ROTOR0_PZ -0.3000
|
||||||
|
param set-default CA_ROTOR1_AX 1.0000
|
||||||
|
param set-default CA_ROTOR1_AY 0.0000
|
||||||
|
param set-default CA_ROTOR1_AZ 0.0000
|
||||||
|
param set-default CA_ROTOR1_KM 0.0000
|
||||||
|
param set-default CA_ROTOR1_PX 0.0000
|
||||||
|
param set-default CA_ROTOR1_PY 0.3000
|
||||||
|
param set-default CA_ROTOR1_PZ -0.3000
|
||||||
|
param set-default CA_ROTOR2_AX 1.0000
|
||||||
|
param set-default CA_ROTOR2_AY 0.0000
|
||||||
|
param set-default CA_ROTOR2_AZ 0.0000
|
||||||
|
param set-default CA_ROTOR2_KM 0.0000
|
||||||
|
param set-default CA_ROTOR2_PX 0.0000
|
||||||
|
param set-default CA_ROTOR2_PY 0.3000
|
||||||
|
param set-default CA_ROTOR2_PZ 0.3000
|
||||||
|
param set-default CA_ROTOR3_AX 1.0000
|
||||||
|
param set-default CA_ROTOR3_AY 0.0000
|
||||||
|
param set-default CA_ROTOR3_AZ 0.0000
|
||||||
|
param set-default CA_ROTOR3_KM 0.0000
|
||||||
|
param set-default CA_ROTOR3_PX 0.0000
|
||||||
|
param set-default CA_ROTOR3_PY -0.3000
|
||||||
|
param set-default CA_ROTOR3_PZ 0.3000
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
|
||||||
|
|
|
@ -65,4 +65,3 @@ param set-default PWM_MAIN_FUNC6 106
|
||||||
param set-default PWM_MAIN_FUNC7 107
|
param set-default PWM_MAIN_FUNC7 107
|
||||||
param set-default PWM_MAIN_FUNC8 108
|
param set-default PWM_MAIN_FUNC8 108
|
||||||
|
|
||||||
set MIXER skip
|
|
||||||
|
|
|
@ -67,5 +67,3 @@ param set-default PWM_MAIN_FUNC9 206
|
||||||
param set-default PWM_MAIN_REV 256
|
param set-default PWM_MAIN_REV 256
|
||||||
|
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
|
||||||
set MIXER custom
|
|
||||||
|
|
|
@ -39,6 +39,28 @@ param set-default RWTO_MAX_PITCH 20
|
||||||
param set-default RWTO_PSP 8
|
param set-default RWTO_PSP 8
|
||||||
param set-default RWTO_AIRSPD_SCL 1.8
|
param set-default RWTO_AIRSPD_SCL 1.8
|
||||||
|
|
||||||
|
param set-default CA_AIRFRAME 1
|
||||||
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 6
|
||||||
|
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS0_TYPE 1
|
||||||
|
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 2
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||||
|
param set-default CA_SV_CS3_TYPE 4
|
||||||
|
param set-default CA_SV_CS4_TYPE 9
|
||||||
|
param set-default CA_SV_CS5_TYPE 10
|
||||||
|
param set-default PWM_MAIN_FUNC3 204
|
||||||
|
param set-default PWM_MAIN_FUNC4 205
|
||||||
|
param set-default PWM_MAIN_FUNC5 101
|
||||||
|
param set-default PWM_MAIN_FUNC6 201
|
||||||
|
param set-default PWM_MAIN_FUNC7 202
|
||||||
|
param set-default PWM_MAIN_FUNC8 203
|
||||||
|
param set-default PWM_MAIN_FUNC9 206
|
||||||
|
param set-default PWM_MAIN_REV 256
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
|
||||||
set MIXER custom
|
|
||||||
|
|
|
@ -39,5 +39,28 @@ param set-default RWTO_MAX_PITCH 20
|
||||||
param set-default RWTO_PSP 8
|
param set-default RWTO_PSP 8
|
||||||
param set-default RWTO_AIRSPD_SCL 1.8
|
param set-default RWTO_AIRSPD_SCL 1.8
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
param set-default CA_AIRFRAME 1
|
||||||
set MIXER custom
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 6
|
||||||
|
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS0_TYPE 1
|
||||||
|
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 2
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||||
|
param set-default CA_SV_CS3_TYPE 4
|
||||||
|
param set-default CA_SV_CS4_TYPE 9
|
||||||
|
param set-default CA_SV_CS5_TYPE 10
|
||||||
|
param set-default PWM_MAIN_FUNC3 204
|
||||||
|
param set-default PWM_MAIN_FUNC4 205
|
||||||
|
param set-default PWM_MAIN_FUNC5 101
|
||||||
|
param set-default PWM_MAIN_FUNC6 201
|
||||||
|
param set-default PWM_MAIN_FUNC7 202
|
||||||
|
param set-default PWM_MAIN_FUNC8 203
|
||||||
|
param set-default PWM_MAIN_FUNC9 206
|
||||||
|
param set-default PWM_MAIN_REV 256
|
||||||
|
|
||||||
|
|
|
@ -35,5 +35,28 @@ param set-default NAV_DLL_ACT 2
|
||||||
|
|
||||||
param set-default RWTO_TKOFF 1
|
param set-default RWTO_TKOFF 1
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
param set-default CA_AIRFRAME 1
|
||||||
set MIXER custom
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 6
|
||||||
|
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS0_TYPE 1
|
||||||
|
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 2
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||||
|
param set-default CA_SV_CS3_TYPE 4
|
||||||
|
param set-default CA_SV_CS4_TYPE 9
|
||||||
|
param set-default CA_SV_CS5_TYPE 10
|
||||||
|
param set-default PWM_MAIN_FUNC3 204
|
||||||
|
param set-default PWM_MAIN_FUNC4 205
|
||||||
|
param set-default PWM_MAIN_FUNC5 101
|
||||||
|
param set-default PWM_MAIN_FUNC6 201
|
||||||
|
param set-default PWM_MAIN_FUNC7 202
|
||||||
|
param set-default PWM_MAIN_FUNC8 203
|
||||||
|
param set-default PWM_MAIN_FUNC9 206
|
||||||
|
param set-default PWM_MAIN_REV 256
|
||||||
|
|
||||||
|
|
|
@ -37,5 +37,28 @@ param set-default RWTO_MAX_PITCH 20
|
||||||
param set-default RWTO_PSP 8
|
param set-default RWTO_PSP 8
|
||||||
param set-default RWTO_AIRSPD_SCL 1.8
|
param set-default RWTO_AIRSPD_SCL 1.8
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
param set-default CA_AIRFRAME 1
|
||||||
set MIXER custom
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 6
|
||||||
|
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS0_TYPE 1
|
||||||
|
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 2
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||||
|
param set-default CA_SV_CS3_TYPE 4
|
||||||
|
param set-default CA_SV_CS4_TYPE 9
|
||||||
|
param set-default CA_SV_CS5_TYPE 10
|
||||||
|
param set-default PWM_MAIN_FUNC3 204
|
||||||
|
param set-default PWM_MAIN_FUNC4 205
|
||||||
|
param set-default PWM_MAIN_FUNC5 101
|
||||||
|
param set-default PWM_MAIN_FUNC6 201
|
||||||
|
param set-default PWM_MAIN_FUNC7 202
|
||||||
|
param set-default PWM_MAIN_FUNC8 203
|
||||||
|
param set-default PWM_MAIN_FUNC9 206
|
||||||
|
param set-default PWM_MAIN_REV 256
|
||||||
|
|
||||||
|
|
|
@ -44,5 +44,28 @@ param set-default FW_USE_NPFG 1
|
||||||
|
|
||||||
param set-default RWTO_TKOFF 1
|
param set-default RWTO_TKOFF 1
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
param set-default CA_AIRFRAME 1
|
||||||
set MIXER custom
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 6
|
||||||
|
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS0_TYPE 1
|
||||||
|
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 2
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||||
|
param set-default CA_SV_CS3_TYPE 4
|
||||||
|
param set-default CA_SV_CS4_TYPE 9
|
||||||
|
param set-default CA_SV_CS5_TYPE 10
|
||||||
|
param set-default PWM_MAIN_FUNC3 204
|
||||||
|
param set-default PWM_MAIN_FUNC4 205
|
||||||
|
param set-default PWM_MAIN_FUNC5 101
|
||||||
|
param set-default PWM_MAIN_FUNC6 201
|
||||||
|
param set-default PWM_MAIN_FUNC7 202
|
||||||
|
param set-default PWM_MAIN_FUNC8 203
|
||||||
|
param set-default PWM_MAIN_FUNC9 206
|
||||||
|
param set-default PWM_MAIN_REV 256
|
||||||
|
|
||||||
|
|
|
@ -81,5 +81,3 @@ param set-default VT_FW_MOT_OFFID 1234
|
||||||
param set-default VT_B_TRANS_DUR 8
|
param set-default VT_B_TRANS_DUR 8
|
||||||
param set-default VT_TYPE 2
|
param set-default VT_TYPE 2
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
|
|
||||||
set MIXER custom
|
|
||||||
|
|
|
@ -76,5 +76,3 @@ param set-default VT_TYPE 0
|
||||||
|
|
||||||
param set-default WV_EN 0
|
param set-default WV_EN 0
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/quad_x_vtol.main.mix
|
|
||||||
set MIXER custom
|
|
||||||
|
|
|
@ -84,5 +84,3 @@ param set-default VT_MOT_ID 1234
|
||||||
param set-default VT_TILT_TRANS 0.6
|
param set-default VT_TILT_TRANS 0.6
|
||||||
param set-default VT_TYPE 1
|
param set-default VT_TYPE 1
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/tiltrotor_sitl.main.mix
|
|
||||||
set MIXER custom
|
|
||||||
|
|
|
@ -5,48 +5,14 @@
|
||||||
# @type Standard VTOL
|
# @type Standard VTOL
|
||||||
#
|
#
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.vtol_defaults
|
. ${R}etc/init.d-posix/airframes/1040_standard_vtol
|
||||||
|
|
||||||
param set-default FW_L1_PERIOD 12
|
# Gimbal
|
||||||
param set-default FW_PR_FF 0.2
|
param set-default PWM_MAIN_FUNC9 420
|
||||||
param set-default FW_PR_P 0.9
|
param set-default PWM_MAIN_FUNC10 421
|
||||||
param set-default FW_PSP_OFF 2
|
param set-default PWM_MAIN_FUNC11 422
|
||||||
param set-default FW_P_LIM_MIN -15
|
|
||||||
param set-default FW_RR_FF 0.1
|
|
||||||
param set-default FW_RR_P 0.3
|
|
||||||
param set-default FW_THR_TRIM 0.25
|
|
||||||
param set-default FW_THR_MAX 0.6
|
|
||||||
param set-default FW_THR_MIN 0.05
|
|
||||||
param set-default FW_T_ALT_TC 2
|
|
||||||
param set-default FW_T_CLMB_MAX 8
|
|
||||||
param set-default FW_T_HRATE_FF 0.5
|
|
||||||
param set-default FW_T_SINK_MAX 2.7
|
|
||||||
param set-default FW_T_SINK_MIN 2.2
|
|
||||||
param set-default FW_T_TAS_TC 2
|
|
||||||
|
|
||||||
param set-default MC_ROLLRATE_P 0.3
|
|
||||||
param set-default MC_YAW_P 1.6
|
|
||||||
|
|
||||||
param set-default MIS_TAKEOFF_ALT 10
|
|
||||||
|
|
||||||
param set-default MPC_ACC_HOR_MAX 2
|
|
||||||
param set-default MPC_XY_P 0.8
|
|
||||||
param set-default MPC_XY_VEL_P_ACC 3
|
|
||||||
param set-default MPC_XY_VEL_I_ACC 4
|
|
||||||
param set-default MPC_XY_VEL_D_ACC 0.1
|
|
||||||
|
|
||||||
param set-default NAV_ACC_RAD 5
|
|
||||||
|
|
||||||
param set-default VT_FWD_THRUST_EN 4
|
|
||||||
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_B_TRANS_DUR 8
|
|
||||||
param set-default VT_TYPE 2
|
|
||||||
|
|
||||||
param set-default RC_MAP_AUX1 8
|
param set-default RC_MAP_AUX1 8
|
||||||
param set-default RC_MAP_AUX2 9
|
param set-default RC_MAP_AUX2 9
|
||||||
param set-default RC_MAP_AUX3 10
|
param set-default RC_MAP_AUX3 10
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
|
|
||||||
set MIXER custom
|
|
||||||
|
|
|
@ -1 +0,0 @@
|
||||||
mixer append /dev/pwm_output0 etc/mixers-sitl/package_drop.aux.mix
|
|
|
@ -36,4 +36,3 @@ param set-default PWM_MAIN_FUNC2 201
|
||||||
param set-default PWM_MAIN_FUNC6 101
|
param set-default PWM_MAIN_FUNC6 101
|
||||||
param set-default PWM_MAIN_FUNC7 101
|
param set-default PWM_MAIN_FUNC7 101
|
||||||
|
|
||||||
set MIXER_FILE skip
|
|
||||||
|
|
|
@ -36,4 +36,3 @@ param set-default PWM_MAIN_FUNC2 101
|
||||||
param set-default PWM_MAIN_FUNC6 102
|
param set-default PWM_MAIN_FUNC6 102
|
||||||
param set-default PWM_MAIN_FUNC7 102
|
param set-default PWM_MAIN_FUNC7 102
|
||||||
|
|
||||||
set MIXER_FILE skip
|
|
||||||
|
|
|
@ -35,4 +35,11 @@ param set-default CBRK_AIRSPD_CHK 162128
|
||||||
param set-default GND_MAX_ANG 0.6
|
param set-default GND_MAX_ANG 0.6
|
||||||
param set-default GND_WHEEL_BASE 3.0
|
param set-default GND_WHEEL_BASE 3.0
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/rover_ackermann_sitl.main.mix
|
param set-default CA_AIRFRAME 5
|
||||||
|
|
||||||
|
param set-default CA_R_REV 1
|
||||||
|
param set-default PWM_MAIN_FUNC1 201
|
||||||
|
param set-default PWM_MAIN_FUNC2 201
|
||||||
|
param set-default PWM_MAIN_FUNC6 101
|
||||||
|
param set-default PWM_MAIN_FUNC7 101
|
||||||
|
|
||||||
|
|
|
@ -46,4 +46,3 @@ param set-default CA_R_REV 3
|
||||||
param set-default PWM_MAIN_FUNC1 101
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
param set-default PWM_MAIN_FUNC2 102
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
|
||||||
set MIXER skip
|
|
||||||
|
|
|
@ -44,5 +44,25 @@ param set-default FW_THR_TRIM 0.8
|
||||||
param set-default FW_THR_IDLE 0
|
param set-default FW_THR_IDLE 0
|
||||||
param set-default COM_DISARM_PRFLT 0
|
param set-default COM_DISARM_PRFLT 0
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/autogyro_sitl.main.mix
|
param set-default CA_AIRFRAME 1
|
||||||
set MIXER custom
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 3
|
||||||
|
param set-default CA_SV_CS0_TRQ_R 0
|
||||||
|
param set-default CA_SV_CS0_TRQ_Y 1
|
||||||
|
param set-default CA_SV_CS0_TYPE 4
|
||||||
|
param set-default CA_SV_CS1_TRQ_P 0
|
||||||
|
param set-default CA_SV_CS1_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 1
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default PWM_MAIN_FUNC1 201
|
||||||
|
param set-default PWM_MAIN_FUNC2 101
|
||||||
|
param set-default PWM_MAIN_FUNC3 202
|
||||||
|
param set-default PWM_MAIN_FUNC4 203
|
||||||
|
param set-default PWM_MAIN_FUNC5 407
|
||||||
|
param set-default PWM_MAIN_FUNC6 408
|
||||||
|
param set-default PWM_MAIN_FUNC7 409
|
||||||
|
|
||||||
|
|
|
@ -50,5 +50,25 @@ param set-default FW_THR_CRUISE 0.8
|
||||||
param set-default FW_THR_IDLE 0
|
param set-default FW_THR_IDLE 0
|
||||||
param set-default COM_DISARM_PRFLT 0
|
param set-default COM_DISARM_PRFLT 0
|
||||||
|
|
||||||
set MIXER_FILE etc/mixers-sitl/autogyro_sitl.main.mix
|
param set-default CA_AIRFRAME 1
|
||||||
set MIXER custom
|
|
||||||
|
param set-default CA_ROTOR_COUNT 1
|
||||||
|
param set-default CA_ROTOR0_PX 0.3
|
||||||
|
|
||||||
|
param set-default CA_SV_CS_COUNT 3
|
||||||
|
param set-default CA_SV_CS0_TRQ_R 0
|
||||||
|
param set-default CA_SV_CS0_TRQ_Y 1
|
||||||
|
param set-default CA_SV_CS0_TYPE 4
|
||||||
|
param set-default CA_SV_CS1_TRQ_P 0
|
||||||
|
param set-default CA_SV_CS1_TRQ_R -0.5
|
||||||
|
param set-default CA_SV_CS1_TYPE 1
|
||||||
|
param set-default CA_SV_CS2_TRQ_P 1
|
||||||
|
param set-default CA_SV_CS2_TYPE 3
|
||||||
|
param set-default PWM_MAIN_FUNC1 201
|
||||||
|
param set-default PWM_MAIN_FUNC2 101
|
||||||
|
param set-default PWM_MAIN_FUNC3 202
|
||||||
|
param set-default PWM_MAIN_FUNC4 203
|
||||||
|
param set-default PWM_MAIN_FUNC5 407
|
||||||
|
param set-default PWM_MAIN_FUNC6 408
|
||||||
|
param set-default PWM_MAIN_FUNC7 409
|
||||||
|
|
||||||
|
|
|
@ -37,4 +37,3 @@ param set-default PWM_MAIN_FUNC2 102
|
||||||
param set-default PWM_MAIN_FUNC3 201
|
param set-default PWM_MAIN_FUNC3 201
|
||||||
param set-default PWM_MAIN_FUNC4 103
|
param set-default PWM_MAIN_FUNC4 103
|
||||||
|
|
||||||
set MIXER skip
|
|
||||||
|
|
|
@ -9,4 +9,24 @@
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
. ${R}etc/init.d/rc.mc_defaults
|
||||||
|
|
||||||
set MIXER quad_w
|
|
||||||
|
param set-default CA_AIRFRAME 0
|
||||||
|
|
||||||
|
param set-default CA_ROTOR_COUNT 4
|
||||||
|
param set-default CA_ROTOR0_PX 0.1515
|
||||||
|
param set-default CA_ROTOR0_PY 0.245
|
||||||
|
param set-default CA_ROTOR0_KM 0.05
|
||||||
|
param set-default CA_ROTOR1_PX -0.1515
|
||||||
|
param set-default CA_ROTOR1_PY -0.1875
|
||||||
|
param set-default CA_ROTOR1_KM 0.05
|
||||||
|
param set-default CA_ROTOR2_PX 0.1515
|
||||||
|
param set-default CA_ROTOR2_PY -0.245
|
||||||
|
param set-default CA_ROTOR2_KM -0.05
|
||||||
|
param set-default CA_ROTOR3_PX -0.1515
|
||||||
|
param set-default CA_ROTOR3_PY 0.1875
|
||||||
|
param set-default CA_ROTOR3_KM -0.05
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
|
|
@ -26,4 +26,29 @@ param set-default TRIG_MODE 4
|
||||||
param set-default MNT_MODE_IN 4
|
param set-default MNT_MODE_IN 4
|
||||||
param set-default MNT_DO_STAB 2
|
param set-default MNT_DO_STAB 2
|
||||||
|
|
||||||
set MIXER hexa_x
|
|
||||||
|
param set-default CA_ROTOR0_PX 0.0
|
||||||
|
param set-default CA_ROTOR0_PY 1.0
|
||||||
|
param set-default CA_ROTOR0_KM -0.05
|
||||||
|
param set-default CA_ROTOR1_PX 0.0
|
||||||
|
param set-default CA_ROTOR1_PY -1.0
|
||||||
|
param set-default CA_ROTOR1_KM 0.05
|
||||||
|
param set-default CA_ROTOR2_PX 0.866025
|
||||||
|
param set-default CA_ROTOR2_PY -0.5
|
||||||
|
param set-default CA_ROTOR2_KM -0.05
|
||||||
|
param set-default CA_ROTOR3_PX -0.866025
|
||||||
|
param set-default CA_ROTOR3_PY 0.5
|
||||||
|
param set-default CA_ROTOR3_KM 0.05
|
||||||
|
param set-default CA_ROTOR4_PX 0.866025
|
||||||
|
param set-default CA_ROTOR4_PY 0.5
|
||||||
|
param set-default CA_ROTOR4_KM 0.05
|
||||||
|
param set-default CA_ROTOR5_PX -0.866025
|
||||||
|
param set-default CA_ROTOR5_PY -0.5
|
||||||
|
param set-default CA_ROTOR5_KM -0.05
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
param set-default PWM_MAIN_FUNC5 105
|
||||||
|
param set-default PWM_MAIN_FUNC6 106
|
||||||
|
|
|
@ -28,4 +28,39 @@ param set-default MNT_MODE_IN 4
|
||||||
param set-default MNT_MODE_OUT 2
|
param set-default MNT_MODE_OUT 2
|
||||||
param set-default MAV_PROTO_VER 2
|
param set-default MAV_PROTO_VER 2
|
||||||
|
|
||||||
set MIXER hexa_x
|
param set-default CA_AIRFRAME 0
|
||||||
|
param set-default CA_ROTOR_COUNT 6
|
||||||
|
|
||||||
|
param set-default CA_ROTOR0_PX 0.0
|
||||||
|
param set-default CA_ROTOR0_PY 1.0
|
||||||
|
param set-default CA_ROTOR0_KM -0.05
|
||||||
|
param set-default CA_ROTOR1_PX 0.0
|
||||||
|
param set-default CA_ROTOR1_PY -1.0
|
||||||
|
param set-default CA_ROTOR1_KM 0.05
|
||||||
|
param set-default CA_ROTOR2_PX 0.866025
|
||||||
|
param set-default CA_ROTOR2_PY -0.5
|
||||||
|
param set-default CA_ROTOR2_KM -0.05
|
||||||
|
param set-default CA_ROTOR3_PX -0.866025
|
||||||
|
param set-default CA_ROTOR3_PY 0.5
|
||||||
|
param set-default CA_ROTOR3_KM 0.05
|
||||||
|
param set-default CA_ROTOR4_PX 0.866025
|
||||||
|
param set-default CA_ROTOR4_PY 0.5
|
||||||
|
param set-default CA_ROTOR4_KM 0.05
|
||||||
|
param set-default CA_ROTOR5_PX -0.866025
|
||||||
|
param set-default CA_ROTOR5_PY -0.5
|
||||||
|
param set-default CA_ROTOR5_KM -0.05
|
||||||
|
|
||||||
|
param set-default PWM_MAIN_FUNC1 101
|
||||||
|
param set-default PWM_MAIN_FUNC2 102
|
||||||
|
param set-default PWM_MAIN_FUNC3 103
|
||||||
|
param set-default PWM_MAIN_FUNC4 104
|
||||||
|
param set-default PWM_MAIN_FUNC5 105
|
||||||
|
param set-default PWM_MAIN_FUNC6 106
|
||||||
|
# Gimbal
|
||||||
|
param set-default PWM_MAIN_FUNC7 420
|
||||||
|
param set-default PWM_MAIN_FUNC8 421
|
||||||
|
param set-default PWM_MAIN_FUNC9 422
|
||||||
|
# Landing gear
|
||||||
|
param set-default PWM_MAIN_FUNC10 400
|
||||||
|
param set-default PWM_MAIN_FUNC11 400
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,4 @@
|
||||||
|
|
||||||
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
|
|
||||||
|
|
||||||
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
|
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
|
||||||
|
|
||||||
# shellcheck disable=SC2154
|
# shellcheck disable=SC2154
|
||||||
|
|
|
@ -1,62 +0,0 @@
|
||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# @name Typhoon H480 SITL
|
|
||||||
#
|
|
||||||
# @type Hexarotor x
|
|
||||||
#
|
|
||||||
|
|
||||||
. ${R}etc/init.d/rc.mc_defaults
|
|
||||||
|
|
||||||
param set-default MAV_TYPE 13
|
|
||||||
|
|
||||||
param set-default MC_PITCHRATE_P 0.0800
|
|
||||||
param set-default MC_PITCHRATE_I 0.0400
|
|
||||||
param set-default MC_PITCHRATE_D 0.0010
|
|
||||||
param set-default MC_PITCH_P 9.0
|
|
||||||
param set-default MC_ROLLRATE_P 0.0800
|
|
||||||
param set-default MC_ROLLRATE_I 0.0400
|
|
||||||
param set-default MC_ROLLRATE_D 0.0010
|
|
||||||
param set-default MC_ROLL_P 9.0
|
|
||||||
|
|
||||||
param set-default MPC_XY_VEL_I_ACC 4
|
|
||||||
param set-default MPC_XY_VEL_P_ACC 3
|
|
||||||
|
|
||||||
param set-default RTL_DESCEND_ALT 10
|
|
||||||
param set-default RTL_LAND_DELAY 0
|
|
||||||
|
|
||||||
param set-default TRIG_INTERFACE 3
|
|
||||||
param set-default TRIG_MODE 4
|
|
||||||
param set-default MNT_MODE_IN 0
|
|
||||||
param set-default MAV_PROTO_VER 2
|
|
||||||
|
|
||||||
param set-default CA_AIRFRAME 0
|
|
||||||
param set-default CA_ROTOR_COUNT 6
|
|
||||||
|
|
||||||
param set-default CA_ROTOR0_PX 0.0
|
|
||||||
param set-default CA_ROTOR0_PY 1.0
|
|
||||||
param set-default CA_ROTOR0_KM -0.05
|
|
||||||
param set-default CA_ROTOR1_PX 0.0
|
|
||||||
param set-default CA_ROTOR1_PY -1.0
|
|
||||||
param set-default CA_ROTOR1_KM 0.05
|
|
||||||
param set-default CA_ROTOR2_PX 0.866025
|
|
||||||
param set-default CA_ROTOR2_PY -0.5
|
|
||||||
param set-default CA_ROTOR2_KM -0.05
|
|
||||||
param set-default CA_ROTOR3_PX -0.866025
|
|
||||||
param set-default CA_ROTOR3_PY 0.5
|
|
||||||
param set-default CA_ROTOR3_KM 0.05
|
|
||||||
param set-default CA_ROTOR4_PX 0.866025
|
|
||||||
param set-default CA_ROTOR4_PY 0.5
|
|
||||||
param set-default CA_ROTOR4_KM 0.05
|
|
||||||
param set-default CA_ROTOR5_PX -0.866025
|
|
||||||
param set-default CA_ROTOR5_PY -0.5
|
|
||||||
param set-default CA_ROTOR5_KM -0.05
|
|
||||||
|
|
||||||
param set-default PWM_MAIN_FUNC1 101
|
|
||||||
param set-default PWM_MAIN_FUNC2 102
|
|
||||||
param set-default PWM_MAIN_FUNC3 103
|
|
||||||
param set-default PWM_MAIN_FUNC4 104
|
|
||||||
param set-default PWM_MAIN_FUNC5 105
|
|
||||||
param set-default PWM_MAIN_FUNC6 106
|
|
||||||
|
|
||||||
set MIXER skip
|
|
||||||
set MIXER_AUX none
|
|
|
@ -1,8 +0,0 @@
|
||||||
|
|
||||||
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
|
|
||||||
|
|
||||||
# shellcheck disable=SC2154
|
|
||||||
mavlink stream -r 10 -s MOUNT_ORIENTATION -u $udp_gcs_port_local
|
|
||||||
# shellcheck disable=SC2154
|
|
||||||
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u $udp_offboard_port_local
|
|
||||||
mavlink stream -r 10 -s MOUNT_ORIENTATION -u $udp_offboard_port_local
|
|
|
@ -33,10 +33,8 @@
|
||||||
|
|
||||||
px4_add_romfs_files(
|
px4_add_romfs_files(
|
||||||
10016_iris
|
10016_iris
|
||||||
10017_iris_ctrlalloc
|
|
||||||
10018_iris_foggy_lidar
|
10018_iris_foggy_lidar
|
||||||
10019_omnicopter
|
10019_omnicopter
|
||||||
10020_if750a
|
|
||||||
10030_px4vision
|
10030_px4vision
|
||||||
10040_quadx
|
10040_quadx
|
||||||
10041_airplane
|
10041_airplane
|
||||||
|
@ -47,19 +45,16 @@ px4_add_romfs_files(
|
||||||
1012_iris_rplidar
|
1012_iris_rplidar
|
||||||
1013_iris_vision
|
1013_iris_vision
|
||||||
1013_iris_vision.post
|
1013_iris_vision.post
|
||||||
1014_solo
|
|
||||||
1015_iris_obs_avoid
|
1015_iris_obs_avoid
|
||||||
1015_iris_obs_avoid.post
|
1015_iris_obs_avoid.post
|
||||||
1017_iris_opt_flow_mockup
|
1017_iris_opt_flow_mockup
|
||||||
1018_iris_vision_velocity
|
1018_iris_vision_velocity
|
||||||
1019_iris_dual_gps
|
1019_iris_dual_gps
|
||||||
1020_uuv_generic
|
|
||||||
1021_uuv_hippocampus
|
1021_uuv_hippocampus
|
||||||
1022_uuv_bluerov2_heavy
|
1022_uuv_bluerov2_heavy
|
||||||
1030_plane
|
1030_plane
|
||||||
1031_plane_cam
|
1031_plane_cam
|
||||||
1032_plane_catapult
|
1032_plane_catapult
|
||||||
1033_plane_lidar
|
|
||||||
1033_rascal
|
1033_rascal
|
||||||
1034_rascal-electric
|
1034_rascal-electric
|
||||||
1035_techpod
|
1035_techpod
|
||||||
|
@ -70,7 +65,7 @@ px4_add_romfs_files(
|
||||||
1041_tailsitter
|
1041_tailsitter
|
||||||
1042_tiltrotor
|
1042_tiltrotor
|
||||||
1043_standard_vtol_drop
|
1043_standard_vtol_drop
|
||||||
1043_standard_vtol_drop.post
|
1044_plane_lidar
|
||||||
1060_rover
|
1060_rover
|
||||||
1061_r1_rover
|
1061_r1_rover
|
||||||
1062_tf-r1
|
1062_tf-r1
|
||||||
|
@ -82,6 +77,4 @@ px4_add_romfs_files(
|
||||||
2507_cloudship
|
2507_cloudship
|
||||||
6011_typhoon_h480
|
6011_typhoon_h480
|
||||||
6011_typhoon_h480.post
|
6011_typhoon_h480.post
|
||||||
6012_typhoon_h480_ctrlalloc
|
|
||||||
6012_typhoon_h480_ctrlalloc.post
|
|
||||||
)
|
)
|
||||||
|
|
|
@ -24,7 +24,7 @@ fi
|
||||||
|
|
||||||
# initialize script variables
|
# initialize script variables
|
||||||
set IO_PRESENT no
|
set IO_PRESENT no
|
||||||
set MIXER none
|
set MIXER skip
|
||||||
set MIXER_AUX none
|
set MIXER_AUX none
|
||||||
set MIXER_FILE none
|
set MIXER_FILE none
|
||||||
set OUTPUT_MODE sim
|
set OUTPUT_MODE sim
|
||||||
|
|
|
@ -1,43 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# Copyright (c) 2018 PX4 Development Team. All rights reserved.
|
|
||||||
#
|
|
||||||
# Redistribution and use in source and binary forms, with or without
|
|
||||||
# modification, are permitted provided that the following conditions
|
|
||||||
# are met:
|
|
||||||
#
|
|
||||||
# 1. Redistributions of source code must retain the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer.
|
|
||||||
# 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer in
|
|
||||||
# the documentation and/or other materials provided with the
|
|
||||||
# distribution.
|
|
||||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
# used to endorse or promote products derived from this software
|
|
||||||
# without specific prior written permission.
|
|
||||||
#
|
|
||||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
# POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
#
|
|
||||||
############################################################################
|
|
||||||
|
|
||||||
px4_add_romfs_files(
|
|
||||||
autogyro_sitl.main.mix
|
|
||||||
delta_wing_sitl.main.mix
|
|
||||||
package_drop.aux.mix
|
|
||||||
plane_sitl.main.mix
|
|
||||||
quad_x_vtol.main.mix
|
|
||||||
standard_vtol_sitl.main.mix
|
|
||||||
tiltrotor_sitl.main.mix
|
|
||||||
uuv_x_sitl.main.mix
|
|
||||||
)
|
|
|
@ -1,37 +0,0 @@
|
||||||
Mixer for SITL autogyro.
|
|
||||||
=========================================================
|
|
||||||
|
|
||||||
# 0 mixer for the rudder (Rotor roll)
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 2 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# 1 mixer for the pusher/puller throttle
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 3 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# 2 mixer for the aileron
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 0 -10000 -10000 0 -10000 10000
|
|
||||||
|
|
||||||
# 3 mixer for the elevator (Rotor pitch)
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 1 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# 4 mixer for the prerotator AUX1
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 5 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# 5 mixer for the manual elevator AUX2
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 6 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# 6 mixer for the release device AUX3
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 7 10000 10000 0 -10000 10000
|
|
|
@ -1,38 +0,0 @@
|
||||||
Mixer for SITL plane
|
|
||||||
=========================================================
|
|
||||||
|
|
||||||
Z:
|
|
||||||
|
|
||||||
Z:
|
|
||||||
|
|
||||||
# mixer for the rudder
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 2 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the flaps
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 4 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the pusher/puller throttle
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 3 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the left aileron
|
|
||||||
M: 2
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 0 -4000 -4000 0 -10000 10000
|
|
||||||
S: 0 1 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the right aileron
|
|
||||||
M: 2
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 0 4000 4000 0 -10000 10000
|
|
||||||
S: 0 1 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the elevator
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 1 -10000 -10000 0 -10000 10000
|
|
|
@ -1,12 +0,0 @@
|
||||||
|
|
||||||
# Roll channel for mount
|
|
||||||
M: 1
|
|
||||||
S: 3 5 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# Pitch channel for mount
|
|
||||||
M: 1
|
|
||||||
S: 3 6 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# Yaw channel for mount
|
|
||||||
M: 1
|
|
||||||
S: 3 7 10000 10000 0 -10000 10000
|
|
|
@ -1,43 +0,0 @@
|
||||||
Mixer for SITL plane
|
|
||||||
=========================================================
|
|
||||||
|
|
||||||
Z:
|
|
||||||
|
|
||||||
Z:
|
|
||||||
|
|
||||||
# mixer for the rudder
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 2 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the flaps
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 4 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the pusher/puller throttle
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 3 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the left aileron
|
|
||||||
M: 2
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 0 -10000 -10000 0 -10000 10000
|
|
||||||
S: 0 5 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the right aileron
|
|
||||||
M: 2
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 0 10000 10000 0 -10000 10000
|
|
||||||
S: 0 5 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the elevator
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 1 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the flaps
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 0 4 10000 10000 0 -10000 10000
|
|
|
@ -1,16 +0,0 @@
|
||||||
Mixer for the gazebo tailsitter model
|
|
||||||
=====================================
|
|
||||||
|
|
||||||
R: 4x
|
|
||||||
|
|
||||||
Z:
|
|
||||||
|
|
||||||
# left elevon
|
|
||||||
M: 2
|
|
||||||
S: 1 0 -10000 -10000 0 -10000 10000
|
|
||||||
S: 1 1 -10000 -10000 0 -10000 10000
|
|
||||||
|
|
||||||
# right elevon
|
|
||||||
M: 2
|
|
||||||
S: 1 0 10000 10000 0 -10000 10000
|
|
||||||
S: 1 1 -10000 -10000 0 -10000 10000
|
|
|
@ -1,26 +0,0 @@
|
||||||
Mixer for standard vtol plane (SITL) with motor x configuration
|
|
||||||
=========================================================
|
|
||||||
|
|
||||||
This file defines a single mixer for a standard vtol plane (SITL gazebo) with motors in X configuration. The plane has two ailerons and one elevator.
|
|
||||||
|
|
||||||
R: 4x
|
|
||||||
|
|
||||||
# mixer for the pusher/puller throttle
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 3 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the left aileron
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 0 -10000 -10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the right aileron
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 0 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the elevator
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 1 10000 10000 0 -10000 10000
|
|
|
@ -1,41 +0,0 @@
|
||||||
Mixer for quad tiltrotor (x motor configuration)
|
|
||||||
================================================
|
|
||||||
|
|
||||||
This file defines a single mixer for a tiltrotor (SITL gazebo) with motors in X configuration. The plane has two ailerons and one elevator.
|
|
||||||
|
|
||||||
R: 4x
|
|
||||||
|
|
||||||
# tilt servo motor 1
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 8 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# tilt servo motor 2
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 8 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# tilt servo motor 3
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 8 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# tilt servo motor 4
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 8 0 20000 -10000 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the left aileron
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 0 -10000 -10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the right aileron
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 0 10000 10000 0 -10000 10000
|
|
||||||
|
|
||||||
# mixer for the elevator
|
|
||||||
M: 1
|
|
||||||
O: 10000 10000 0 -10000 10000
|
|
||||||
S: 1 1 10000 10000 0 -10000 10000
|
|
|
@ -1,25 +0,0 @@
|
||||||
Mixer for Unmanned Underwater Vehicles (UUV) with X-Motor configuration
|
|
||||||
==========================================================================
|
|
||||||
|
|
||||||
# @board px4_fmu-v2 exclude
|
|
||||||
|
|
||||||
M: 4
|
|
||||||
S: 0 0 -4000 -4000 0 -4000 4000
|
|
||||||
S: 0 1 -4000 -4000 0 -4000 4000
|
|
||||||
S: 0 2 +4000 +4000 0 -4000 4000
|
|
||||||
S: 0 3 +4000 +4000 0 -4000 4000
|
|
||||||
M: 4
|
|
||||||
S: 0 0 +4000 +4000 0 -4000 4000
|
|
||||||
S: 0 1 -4000 -4000 0 -4000 4000
|
|
||||||
S: 0 2 -4000 -4000 0 -4000 4000
|
|
||||||
S: 0 3 +4000 +4000 0 -4000 4000
|
|
||||||
M: 4
|
|
||||||
S: 0 0 -4000 -4000 0 -4000 4000
|
|
||||||
S: 0 1 +4000 +4000 0 -4000 4000
|
|
||||||
S: 0 2 -4000 -4000 0 -4000 4000
|
|
||||||
S: 0 3 +4000 +4000 0 -4000 4000
|
|
||||||
M: 4
|
|
||||||
S: 0 0 +4000 +4000 0 -4000 4000
|
|
||||||
S: 0 1 +4000 +4000 0 -4000 4000
|
|
||||||
S: 0 2 +4000 +4000 0 -4000 4000
|
|
||||||
S: 0 3 +4000 +4000 0 -4000 4000
|
|
|
@ -146,9 +146,7 @@ set(models
|
||||||
boat
|
boat
|
||||||
cloudship
|
cloudship
|
||||||
glider
|
glider
|
||||||
if750a
|
|
||||||
iris
|
iris
|
||||||
iris_ctrlalloc
|
|
||||||
iris_dual_gps
|
iris_dual_gps
|
||||||
iris_foggy_lidar
|
iris_foggy_lidar
|
||||||
iris_irlock
|
iris_irlock
|
||||||
|
@ -167,14 +165,12 @@ set(models
|
||||||
r1_rover
|
r1_rover
|
||||||
rover
|
rover
|
||||||
shell
|
shell
|
||||||
solo
|
|
||||||
standard_vtol
|
standard_vtol
|
||||||
standard_vtol_drop
|
standard_vtol_drop
|
||||||
tailsitter
|
tailsitter
|
||||||
techpod
|
techpod
|
||||||
tiltrotor
|
tiltrotor
|
||||||
typhoon_h480
|
typhoon_h480
|
||||||
typhoon_h480_ctrlalloc
|
|
||||||
uuv_bluerov2_heavy
|
uuv_bluerov2_heavy
|
||||||
uuv_hippocampus
|
uuv_hippocampus
|
||||||
)
|
)
|
||||||
|
|
Loading…
Reference in New Issue