Added standard vtol and foxtech loong 2160 VTOL models (#21004)

Signed-off-by: Benjamin Perseghetti <bperseghetti@rudislabs.com>
This commit is contained in:
Alejandro Hernández Cordero 2023-01-25 17:32:35 +01:00 committed by GitHub
parent a210c96aa9
commit 90d904bfd4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
20 changed files with 13927 additions and 0 deletions

View File

@ -0,0 +1,108 @@
#!/bin/sh
#
# @name Standard VTOL
#
# @type Standard VTOL
#
. ${R}etc/init.d/rc.vtol_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol}
# TODO: Enable motor failure detection when the
# VTOL no longer reports 0A for all ESCs in SITL
param set-default FD_ACT_EN 0
param set-default FD_ACT_MOT_TOUT 500
param set-default CA_AIRFRAME 2
param set-default CA_ROTOR_COUNT 5
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 CA_ROTOR4_AX 1.0
param set-default CA_ROTOR4_AZ 0.0
param set-default CA_ROTOR4_PX 0.2
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_MIN1 0
param set-default SIM_GZ_EC_MAX1 1000
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_MIN2 0
param set-default SIM_GZ_EC_MAX2 1000
param set-default SIM_GZ_EC_FUNC3 103
param set-default SIM_GZ_EC_MIN3 0
param set-default SIM_GZ_EC_MAX3 1000
param set-default SIM_GZ_EC_FUNC4 104
param set-default SIM_GZ_EC_MIN4 0
param set-default SIM_GZ_EC_MAX4 1000
param set-default SIM_GZ_EC_FUNC5 105
param set-default SIM_GZ_EC_MIN5 0
param set-default SIM_GZ_EC_MAX5 1000
param set-default SIM_GZ_SV_FUNC1 201
param set-default SIM_GZ_SV_FUNC2 202
param set-default SIM_GZ_SV_FUNC3 203
param set-default COM_RC_IN_MODE 1
param set-default ASPD_PRIMARY 1
param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
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 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default FW_L1_PERIOD 12
param set-default FW_PR_FF 0.2
param set-default FW_PR_P 0.9
param set-default FW_PSP_OFF 2
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_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2
param set-default MC_AIRMODE 1
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_B_TRANS_DUR 8
param set-default VT_TYPE 2

View File

@ -0,0 +1,108 @@
#!/bin/sh
#
# @name Standard VTOL
#
# @type Standard VTOL
#
. ${R}etc/init.d/rc.vtol_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=foxtech_loong_2160}
# TODO: Enable motor failure detection when the
# VTOL no longer reports 0A for all ESCs in SITL
param set-default FD_ACT_EN 0
param set-default FD_ACT_MOT_TOUT 500
param set-default CA_AIRFRAME 2
param set-default CA_ROTOR_COUNT 5
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 CA_ROTOR4_AX 1.0
param set-default CA_ROTOR4_AZ 0.0
param set-default CA_ROTOR4_PX 0.2
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_MIN1 0
param set-default SIM_GZ_EC_MAX1 1000
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_MIN2 0
param set-default SIM_GZ_EC_MAX2 1000
param set-default SIM_GZ_EC_FUNC3 103
param set-default SIM_GZ_EC_MIN3 0
param set-default SIM_GZ_EC_MAX3 1000
param set-default SIM_GZ_EC_FUNC4 104
param set-default SIM_GZ_EC_MIN4 0
param set-default SIM_GZ_EC_MAX4 1000
param set-default SIM_GZ_EC_FUNC5 105
param set-default SIM_GZ_EC_MIN5 0
param set-default SIM_GZ_EC_MAX5 1000
param set-default SIM_GZ_SV_FUNC1 201
param set-default SIM_GZ_SV_FUNC2 202
param set-default SIM_GZ_SV_FUNC3 203
param set-default COM_RC_IN_MODE 1
param set-default ASPD_PRIMARY 1
param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
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 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default FW_L1_PERIOD 12
param set-default FW_PR_FF 0.2
param set-default FW_PR_P 0.9
param set-default FW_PSP_OFF 2
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_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2
param set-default MC_AIRMODE 1
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_B_TRANS_DUR 8
param set-default VT_TYPE 2

View File

@ -73,6 +73,8 @@ px4_add_romfs_files(
4001_gz_x500
4002_gz_x500_depth
4003_gz_rc_cessna
4004_gz_standard_vtol
4005_gz_foxtech_loong_2160
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,262 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author/>
<authoring_tool>FBX COLLADA exporter</authoring_tool>
<comments/>
</contributor>
<created>2023-01-04T01:05:20Z</created>
<keywords/>
<modified>2023-01-04T01:05:20Z</modified>
<revision/>
<subject/>
<title/>
<unit meter="0.010000" name="centimeter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_materials>
<material id="FBXASC0481FBXASC032-FBXASC032Default" name="FBXASC0481FBXASC032-FBXASC032Default">
<instance_effect url="#FBXASC0481FBXASC032-FBXASC032Default-fx"/>
</material>
</library_materials>
<library_effects>
<effect id="FBXASC0481FBXASC032-FBXASC032Default-fx" name="FBXASC0481FBXASC032-FBXASC032Default">
<profile_COMMON>
<technique sid="standard">
<phong>
<emission>
<color sid="emission">0.000000 0.000000 0.000000 1.000000</color>
</emission>
<ambient>
<color sid="ambient">0.588235 0.588235 0.588235 1.000000</color>
</ambient>
<diffuse>
<color sid="diffuse">0.588235 0.588235 0.588235 1.000000</color>
</diffuse>
<specular>
<color sid="specular">0.486000 0.486000 0.486000 1.000000</color>
</specular>
<shininess>
<float sid="shininess">2.000000</float>
</shininess>
<reflective>
<color sid="reflective">0.000000 0.000000 0.000000 1.000000</color>
</reflective>
<reflectivity>
<float sid="reflectivity">1.000000</float>
</reflectivity>
<transparent opaque="RGB_ZERO">
<color sid="transparent">1.000000 1.000000 1.000000 1.000000</color>
</transparent>
<transparency>
<float sid="transparency">0.000000</float>
</transparency>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_geometries>
<geometry id="aileron_left-lib" name="aileron_leftMesh">
<mesh>
<source id="aileron_left-POSITION">
<float_array id="aileron_left-POSITION-array" count="48">
-8.508881 -8.085777 -0.718638
-8.508881 -8.085783 -0.353647
4.939667 -6.844479 -0.718638
4.939667 -6.844481 -0.353647
-17.070042 -8.085783 -0.353647
-17.070042 -8.085777 -0.718638
17.070045 -4.887245 -0.718638
17.070038 -4.887245 -0.353647
-8.508881 0.511266 -0.718638
-8.508881 0.511267 0.718638
4.939667 0.511266 -0.718638
4.939667 0.511266 0.642922
-17.070042 0.511266 -0.718638
-17.070042 0.511266 0.718212
17.070045 0.511266 -0.718638
17.070030 0.511267 0.494327
</float_array>
<technique_common>
<accessor source="#aileron_left-POSITION-array" count="16" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="aileron_left-Normal0">
<float_array id="aileron_left-Normal0-array" count="252">
0.004350 -0.126175 0.991998
0.012806 -0.135273 0.990726
0.013164 -0.135857 0.990641
0.012806 -0.135273 0.990726
0.004350 -0.126175 0.991998
0.004220 -0.126103 0.992008
0.046003 -0.998941 -0.000013
0.125672 -0.992072 -0.000006
0.125672 -0.992072 -0.000006
0.125672 -0.992072 -0.000006
0.046003 -0.998941 -0.000013
0.046003 -0.998941 -0.000013
0.013164 -0.135857 0.990641
0.017606 -0.143110 0.989550
0.017606 -0.143110 0.989550
0.017606 -0.143110 0.989550
0.013164 -0.135857 0.990641
0.012806 -0.135273 0.990726
0.159290 -0.987232 -0.000001
0.125672 -0.992072 -0.000006
0.159290 -0.987232 -0.000001
0.125672 -0.992072 -0.000006
0.159290 -0.987232 -0.000001
0.125672 -0.992072 -0.000006
-0.000025 -0.123744 0.992314
0.004220 -0.126103 0.992008
0.004350 -0.126175 0.991998
0.004220 -0.126103 0.992008
-0.000025 -0.123744 0.992314
-0.000025 -0.123744 0.992314
0.000000 -1.000000 -0.000016
0.046003 -0.998941 -0.000013
0.046003 -0.998941 -0.000013
0.046003 -0.998941 -0.000013
0.000000 -1.000000 -0.000016
0.000000 -1.000000 -0.000016
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
</float_array>
<technique_common>
<accessor source="#aileron_left-Normal0-array" count="84" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="aileron_left-UV0">
<float_array id="aileron_left-UV0-array" count="48">
0.250000 0.000000
0.750000 0.000000
0.750000 0.000000
0.750000 1.000000
0.125000 0.000000
0.875000 0.000000
0.875000 0.000000
0.875000 1.000000
0.715060 0.000000
0.715060 1.000000
0.284940 0.000000
0.715060 0.000000
0.076671 0.000000
0.923329 0.000000
0.923329 0.000000
0.923329 1.000000
0.250000 0.290830
0.750000 0.284605
0.125000 0.265730
0.875000 0.259691
0.284940 0.290830
0.715060 0.284605
0.078795 0.225632
0.921382 0.233592
</float_array>
<technique_common>
<accessor source="#aileron_left-UV0-array" count="24" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="aileron_left-VERTEX">
<input semantic="POSITION" source="#aileron_left-POSITION"/>
</vertices>
<triangles count="28" material="FBXASC0481FBXASC032-FBXASC032Default">
<input semantic="VERTEX" offset="0" source="#aileron_left-VERTEX"/>
<input semantic="NORMAL" offset="1" source="#aileron_left-Normal0"/>
<input semantic="TEXCOORD" offset="2" set="0" source="#aileron_left-UV0"/>
<p> 9 0 17 3 1 6 11 2 19 3 3 6 9 4 17 1 5 2 1 6 3 2 7 5 3 8 7 2 9 5 1 10 3 0 11 1 11 12 19 7 13 14 15 14 23 7 15 14 11 16 19 3 17 6 7 18 15 2 19 5 6 20 13 2 21 5 7 22 15 3 23 7 13 24 21 1 25 2 9 26 17 1 27 2 13 28 21 4 29 8 4 30 9 0 31 1 1 32 3 0 33 1 4 34 9 5 35 11 2 36 4 0 37 0 8 38 16 2 39 4 8 40 16 10 41 18 6 42 12 2 43 4 10 44 18 6 45 12 10 46 18 14 47 22 5 48 10 12 49 20 0 50 0 0 51 0 12 52 20 8 53 16 4 54 4 13 55 13 12 56 12 4 57 4 12 58 12 5 59 5 13 60 13 8 61 8 12 62 12 8 63 8 13 64 13 9 65 9 11 66 11 8 67 8 9 68 9 8 69 8 11 70 11 10 71 10 15 72 15 10 73 10 11 74 11 10 75 10 15 76 15 14 77 14 7 78 7 14 79 14 15 80 15 14 81 14 7 82 7 6 83 6</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="aileron_left" name="aileron_left">
<node name="aileron_left" id="aileron_left" sid="aileron_left">
<matrix sid="matrix">-1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 -0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000</matrix>
<instance_geometry url="#aileron_left-lib">
<bind_material>
<technique_common>
<instance_material symbol="FBXASC0481FBXASC032-FBXASC032Default" target="#FBXASC0481FBXASC032-FBXASC032Default"/>
</technique_common>
</bind_material>
</instance_geometry>
<extra>
<technique profile="FCOLLADA">
<visibility>1.000000</visibility>
</technique>
</extra>
</node>
<extra>
<technique profile="MAX3D">
<frame_rate>30.000000</frame_rate>
</technique>
<technique profile="FCOLLADA">
<start_time>0.000000</start_time>
<end_time>3.333333</end_time>
</technique>
</extra>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#aileron_left"/>
</scene>
</COLLADA>

View File

@ -0,0 +1,262 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author/>
<authoring_tool>FBX COLLADA exporter</authoring_tool>
<comments/>
</contributor>
<created>2023-01-04T01:05:21Z</created>
<keywords/>
<modified>2023-01-04T01:05:21Z</modified>
<revision/>
<subject/>
<title/>
<unit meter="0.010000" name="centimeter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_materials>
<material id="FBXASC0481FBXASC032-FBXASC032Default" name="FBXASC0481FBXASC032-FBXASC032Default">
<instance_effect url="#FBXASC0481FBXASC032-FBXASC032Default-fx"/>
</material>
</library_materials>
<library_effects>
<effect id="FBXASC0481FBXASC032-FBXASC032Default-fx" name="FBXASC0481FBXASC032-FBXASC032Default">
<profile_COMMON>
<technique sid="standard">
<phong>
<emission>
<color sid="emission">0.000000 0.000000 0.000000 1.000000</color>
</emission>
<ambient>
<color sid="ambient">0.588235 0.588235 0.588235 1.000000</color>
</ambient>
<diffuse>
<color sid="diffuse">0.588235 0.588235 0.588235 1.000000</color>
</diffuse>
<specular>
<color sid="specular">0.486000 0.486000 0.486000 1.000000</color>
</specular>
<shininess>
<float sid="shininess">2.000000</float>
</shininess>
<reflective>
<color sid="reflective">0.000000 0.000000 0.000000 1.000000</color>
</reflective>
<reflectivity>
<float sid="reflectivity">1.000000</float>
</reflectivity>
<transparent opaque="RGB_ZERO">
<color sid="transparent">1.000000 1.000000 1.000000 1.000000</color>
</transparent>
<transparency>
<float sid="transparency">0.000000</float>
</transparency>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_geometries>
<geometry id="aileron_right-lib" name="aileron_rightMesh">
<mesh>
<source id="aileron_right-POSITION">
<float_array id="aileron_right-POSITION-array" count="48">
-8.508881 -8.085777 -0.718638
-8.508881 -8.085783 -0.353647
4.939667 -6.844479 -0.718638
4.939667 -6.844481 -0.353647
-17.070042 -8.085783 -0.353647
-17.070042 -8.085777 -0.718638
17.070045 -4.887245 -0.718638
17.070038 -4.887245 -0.353647
-8.508881 0.511266 -0.718638
-8.508881 0.511267 0.718638
4.939667 0.511266 -0.718638
4.939667 0.511266 0.642922
-17.070042 0.511266 -0.718638
-17.070042 0.511266 0.718212
17.070045 0.511266 -0.718638
17.070030 0.511267 0.494327
</float_array>
<technique_common>
<accessor source="#aileron_right-POSITION-array" count="16" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="aileron_right-Normal0">
<float_array id="aileron_right-Normal0-array" count="252">
0.004350 -0.126175 0.991998
0.012806 -0.135273 0.990726
0.013164 -0.135857 0.990641
0.012806 -0.135273 0.990726
0.004350 -0.126175 0.991998
0.004220 -0.126103 0.992008
0.046003 -0.998941 -0.000013
0.125672 -0.992072 -0.000006
0.125672 -0.992072 -0.000006
0.125672 -0.992072 -0.000006
0.046003 -0.998941 -0.000013
0.046003 -0.998941 -0.000013
0.013164 -0.135857 0.990641
0.017606 -0.143110 0.989550
0.017606 -0.143110 0.989550
0.017606 -0.143110 0.989550
0.013164 -0.135857 0.990641
0.012806 -0.135273 0.990726
0.159290 -0.987232 -0.000001
0.125672 -0.992072 -0.000006
0.159290 -0.987232 -0.000001
0.125672 -0.992072 -0.000006
0.159290 -0.987232 -0.000001
0.125672 -0.992072 -0.000006
-0.000025 -0.123744 0.992314
0.004220 -0.126103 0.992008
0.004350 -0.126175 0.991998
0.004220 -0.126103 0.992008
-0.000025 -0.123744 0.992314
-0.000025 -0.123744 0.992314
0.000000 -1.000000 -0.000016
0.046003 -0.998941 -0.000013
0.046003 -0.998941 -0.000013
0.046003 -0.998941 -0.000013
0.000000 -1.000000 -0.000016
0.000000 -1.000000 -0.000016
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
-0.000000 1.000000 -0.000000
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
1.000000 -0.000000 0.000015
</float_array>
<technique_common>
<accessor source="#aileron_right-Normal0-array" count="84" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="aileron_right-UV0">
<float_array id="aileron_right-UV0-array" count="48">
0.250000 0.000000
0.750000 0.000000
0.750000 0.000000
0.750000 1.000000
0.125000 0.000000
0.875000 0.000000
0.875000 0.000000
0.875000 1.000000
0.715060 0.000000
0.715060 1.000000
0.284940 0.000000
0.715060 0.000000
0.076671 0.000000
0.923329 0.000000
0.923329 0.000000
0.923329 1.000000
0.250000 0.290830
0.750000 0.284605
0.125000 0.265730
0.875000 0.259691
0.284940 0.290830
0.715060 0.284605
0.078795 0.225632
0.921382 0.233592
</float_array>
<technique_common>
<accessor source="#aileron_right-UV0-array" count="24" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="aileron_right-VERTEX">
<input semantic="POSITION" source="#aileron_right-POSITION"/>
</vertices>
<triangles count="28" material="FBXASC0481FBXASC032-FBXASC032Default">
<input semantic="VERTEX" offset="0" source="#aileron_right-VERTEX"/>
<input semantic="NORMAL" offset="1" source="#aileron_right-Normal0"/>
<input semantic="TEXCOORD" offset="2" set="0" source="#aileron_right-UV0"/>
<p> 9 0 17 3 1 6 11 2 19 3 3 6 9 4 17 1 5 2 1 6 3 2 7 5 3 8 7 2 9 5 1 10 3 0 11 1 11 12 19 7 13 14 15 14 23 7 15 14 11 16 19 3 17 6 7 18 15 2 19 5 6 20 13 2 21 5 7 22 15 3 23 7 13 24 21 1 25 2 9 26 17 1 27 2 13 28 21 4 29 8 4 30 9 0 31 1 1 32 3 0 33 1 4 34 9 5 35 11 2 36 4 0 37 0 8 38 16 2 39 4 8 40 16 10 41 18 6 42 12 2 43 4 10 44 18 6 45 12 10 46 18 14 47 22 5 48 10 12 49 20 0 50 0 0 51 0 12 52 20 8 53 16 4 54 4 13 55 13 12 56 12 4 57 4 12 58 12 5 59 5 13 60 13 8 61 8 12 62 12 8 63 8 13 64 13 9 65 9 11 66 11 8 67 8 9 68 9 8 69 8 11 70 11 10 71 10 15 72 15 10 73 10 11 74 11 10 75 10 15 76 15 14 77 14 7 78 7 14 79 14 15 80 15 14 81 14 7 82 7 6 83 6</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="aileron_right" name="aileron_right">
<node name="aileron_right" id="aileron_right" sid="aileron_right">
<matrix sid="matrix">1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000</matrix>
<instance_geometry url="#aileron_right-lib">
<bind_material>
<technique_common>
<instance_material symbol="FBXASC0481FBXASC032-FBXASC032Default" target="#FBXASC0481FBXASC032-FBXASC032Default"/>
</technique_common>
</bind_material>
</instance_geometry>
<extra>
<technique profile="FCOLLADA">
<visibility>1.000000</visibility>
</technique>
</extra>
</node>
<extra>
<technique profile="MAX3D">
<frame_rate>30.000000</frame_rate>
</technique>
<technique profile="FCOLLADA">
<start_time>0.000000</start_time>
<end_time>3.333333</end_time>
</technique>
</extra>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#aileron_right"/>
</scene>
</COLLADA>

View File

@ -0,0 +1,262 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author/>
<authoring_tool>FBX COLLADA exporter</authoring_tool>
<comments/>
</contributor>
<created>2023-01-04T01:05:23Z</created>
<keywords/>
<modified>2023-01-04T01:05:23Z</modified>
<revision/>
<subject/>
<title/>
<unit meter="0.010000" name="centimeter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_materials>
<material id="FBXASC0481FBXASC032-FBXASC032Default" name="FBXASC0481FBXASC032-FBXASC032Default">
<instance_effect url="#FBXASC0481FBXASC032-FBXASC032Default-fx"/>
</material>
</library_materials>
<library_effects>
<effect id="FBXASC0481FBXASC032-FBXASC032Default-fx" name="FBXASC0481FBXASC032-FBXASC032Default">
<profile_COMMON>
<technique sid="standard">
<phong>
<emission>
<color sid="emission">0.000000 0.000000 0.000000 1.000000</color>
</emission>
<ambient>
<color sid="ambient">0.588235 0.588235 0.588235 1.000000</color>
</ambient>
<diffuse>
<color sid="diffuse">0.588235 0.588235 0.588235 1.000000</color>
</diffuse>
<specular>
<color sid="specular">0.486000 0.486000 0.486000 1.000000</color>
</specular>
<shininess>
<float sid="shininess">2.000000</float>
</shininess>
<reflective>
<color sid="reflective">0.000000 0.000000 0.000000 1.000000</color>
</reflective>
<reflectivity>
<float sid="reflectivity">1.000000</float>
</reflectivity>
<transparent opaque="RGB_ZERO">
<color sid="transparent">1.000000 1.000000 1.000000 1.000000</color>
</transparent>
<transparency>
<float sid="transparency">0.000000</float>
</transparency>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_geometries>
<geometry id="elevator_left-lib" name="elevator_leftMesh">
<mesh>
<source id="elevator_left-POSITION">
<float_array id="elevator_left-POSITION-array" count="48">
18.025543 -15.576103 -0.524075
18.025543 -15.576107 -0.159084
31.474091 -14.334805 -0.524075
31.474091 -14.334805 -0.159084
16.329094 0.045925 -0.524075
15.810318 0.045925 0.524076
29.862923 0.045921 -0.524075
29.375877 0.045925 0.487995
-35.404789 -15.576107 -0.159084
-35.404789 -15.576103 -0.524075
-35.404789 0.045925 -0.524075
-35.404789 0.045925 0.523587
35.406570 -13.420116 -0.524075
35.406570 -13.394806 -0.159084
35.406570 0.045921 -0.524075
35.406570 0.045925 0.445975
</float_array>
<technique_common>
<accessor source="#elevator_left-POSITION-array" count="16" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="elevator_left-Normal0">
<float_array id="elevator_left-Normal0-array" count="252">
0.005639 -0.044047 0.999014
0.001521 -0.043737 0.999042
0.001776 -0.043748 0.999041
0.005639 -0.044047 0.999014
0.001776 -0.043748 0.999041
0.005840 -0.044067 0.999012
0.046003 -0.998941 -0.000008
0.161065 -0.986799 0.016905
0.161065 -0.986799 0.016905
0.161065 -0.986799 0.016905
0.046003 -0.998941 -0.000008
0.046003 -0.998941 -0.000008
0.005639 -0.044047 0.999014
0.008395 -0.044327 0.998982
0.008395 -0.044327 0.998982
0.008395 -0.044327 0.998982
0.005639 -0.044047 0.999014
0.005840 -0.044067 0.999012
0.229390 -0.972750 0.033728
0.161065 -0.986799 0.016905
0.229390 -0.972750 0.033728
0.161065 -0.986799 0.016905
0.229390 -0.972750 0.033728
0.161065 -0.986799 0.016905
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.001521 -0.043737 0.999042
-0.000005 -0.043674 0.999046
-0.000005 -0.043674 0.999046
0.001521 -0.043737 0.999042
-0.000005 -0.043674 0.999046
0.001776 -0.043748 0.999041
0.000000 -1.000000 -0.000010
0.046003 -0.998941 -0.000008
0.046003 -0.998941 -0.000008
0.046003 -0.998941 -0.000008
0.000000 -1.000000 -0.000010
0.000000 -1.000000 -0.000010
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
-0.000000 1.000000 -0.000004
0.000000 1.000000 -0.000003
-0.000000 1.000000 -0.000004
0.000000 1.000000 -0.000003
-0.000000 1.000000 -0.000004
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000001
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000001
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000001
0.000000 1.000000 -0.000001
0.000000 1.000000 0.000000
0.000000 1.000000 -0.000001
0.000000 1.000000 0.000000
0.000000 1.000000 -0.000001
0.000000 1.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
</float_array>
<technique_common>
<accessor source="#elevator_left-Normal0-array" count="84" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="elevator_left-UV0">
<float_array id="elevator_left-UV0-array" count="48">
0.250000 0.000000
0.750000 0.000000
0.750000 0.000000
0.750000 1.000000
0.125000 0.000000
0.875000 0.000000
0.875000 0.000000
0.875000 1.000000
0.250000 0.247131
0.750000 0.172769
0.125000 0.234707
0.875000 0.160663
0.556720 0.000000
0.556720 1.000000
0.443280 0.000000
0.556720 0.000000
0.441864 0.247131
0.558584 0.173020
0.897586 0.000000
0.102414 0.000000
0.898211 0.000000
0.898211 1.000000
0.095974 0.232439
0.905697 0.154750
</float_array>
<technique_common>
<accessor source="#elevator_left-UV0-array" count="24" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="elevator_left-VERTEX">
<input semantic="POSITION" source="#elevator_left-POSITION"/>
</vertices>
<triangles count="28" material="FBXASC0481FBXASC032-FBXASC032Default">
<input semantic="VERTEX" offset="0" source="#elevator_left-VERTEX"/>
<input semantic="NORMAL" offset="1" source="#elevator_left-Normal0"/>
<input semantic="TEXCOORD" offset="2" set="0" source="#elevator_left-UV0"/>
<p> 7 0 11 5 1 9 1 2 2 7 3 11 1 4 2 3 5 6 1 6 3 2 7 5 3 8 7 2 9 5 1 10 3 0 11 1 7 12 11 13 13 20 15 14 23 13 15 20 7 16 11 3 17 6 13 18 21 2 19 5 12 20 18 2 21 5 13 22 21 3 23 7 9 24 14 4 25 8 0 26 0 4 27 8 9 28 14 10 29 16 0 30 0 6 31 10 2 32 4 6 33 10 0 34 0 4 35 8 5 36 9 11 37 17 8 38 12 5 39 9 8 40 12 1 41 2 8 42 13 0 43 1 1 44 3 0 45 1 8 46 13 9 47 15 2 48 4 6 49 10 12 50 19 12 51 19 6 52 10 14 53 22 12 54 12 14 55 14 13 56 13 15 57 15 13 58 13 14 59 14 14 60 14 6 61 6 15 62 15 7 63 7 15 64 15 6 65 6 6 66 6 4 67 4 7 68 7 5 69 5 7 70 7 4 71 4 4 72 4 10 73 10 5 74 5 11 75 11 5 76 5 10 77 10 10 78 10 8 79 8 11 80 11 8 81 8 10 82 10 9 83 9</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="elevator_left" name="elevator_left">
<node name="elevator_left" id="elevator_left" sid="elevator_left">
<matrix sid="matrix">-0.280290 0.000000 0.000000 0.000000 0.000000 0.280290 -0.000000 0.000000 0.000000 0.000000 0.477438 0.000000 0.000000 0.000000 0.000000 1.000000</matrix>
<instance_geometry url="#elevator_left-lib">
<bind_material>
<technique_common>
<instance_material symbol="FBXASC0481FBXASC032-FBXASC032Default" target="#FBXASC0481FBXASC032-FBXASC032Default"/>
</technique_common>
</bind_material>
</instance_geometry>
<extra>
<technique profile="FCOLLADA">
<visibility>1.000000</visibility>
</technique>
</extra>
</node>
<extra>
<technique profile="MAX3D">
<frame_rate>30.000000</frame_rate>
</technique>
<technique profile="FCOLLADA">
<start_time>0.000000</start_time>
<end_time>3.333333</end_time>
</technique>
</extra>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#elevator_left"/>
</scene>
</COLLADA>

View File

@ -0,0 +1,262 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author/>
<authoring_tool>FBX COLLADA exporter</authoring_tool>
<comments/>
</contributor>
<created>2023-01-04T01:05:24Z</created>
<keywords/>
<modified>2023-01-04T01:05:24Z</modified>
<revision/>
<subject/>
<title/>
<unit meter="0.010000" name="centimeter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_materials>
<material id="FBXASC0481FBXASC032-FBXASC032Default" name="FBXASC0481FBXASC032-FBXASC032Default">
<instance_effect url="#FBXASC0481FBXASC032-FBXASC032Default-fx"/>
</material>
</library_materials>
<library_effects>
<effect id="FBXASC0481FBXASC032-FBXASC032Default-fx" name="FBXASC0481FBXASC032-FBXASC032Default">
<profile_COMMON>
<technique sid="standard">
<phong>
<emission>
<color sid="emission">0.000000 0.000000 0.000000 1.000000</color>
</emission>
<ambient>
<color sid="ambient">0.588235 0.588235 0.588235 1.000000</color>
</ambient>
<diffuse>
<color sid="diffuse">0.588235 0.588235 0.588235 1.000000</color>
</diffuse>
<specular>
<color sid="specular">0.486000 0.486000 0.486000 1.000000</color>
</specular>
<shininess>
<float sid="shininess">2.000000</float>
</shininess>
<reflective>
<color sid="reflective">0.000000 0.000000 0.000000 1.000000</color>
</reflective>
<reflectivity>
<float sid="reflectivity">1.000000</float>
</reflectivity>
<transparent opaque="RGB_ZERO">
<color sid="transparent">1.000000 1.000000 1.000000 1.000000</color>
</transparent>
<transparency>
<float sid="transparency">0.000000</float>
</transparency>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_geometries>
<geometry id="elevator_right-lib" name="elevator_rightMesh">
<mesh>
<source id="elevator_right-POSITION">
<float_array id="elevator_right-POSITION-array" count="48">
18.025543 -15.576103 -0.524075
18.025543 -15.576107 -0.159084
31.474091 -14.334805 -0.524075
31.474091 -14.334805 -0.159084
16.329094 0.045925 -0.524075
15.810318 0.045925 0.524076
29.862923 0.045921 -0.524075
29.375877 0.045925 0.487995
-35.404789 -15.576107 -0.159084
-35.404789 -15.576103 -0.524075
-35.404789 0.045925 -0.524075
-35.404789 0.045925 0.523587
35.406570 -13.420116 -0.524075
35.406570 -13.394806 -0.159084
35.406570 0.045921 -0.524075
35.406570 0.045925 0.445975
</float_array>
<technique_common>
<accessor source="#elevator_right-POSITION-array" count="16" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="elevator_right-Normal0">
<float_array id="elevator_right-Normal0-array" count="252">
0.005639 -0.044047 0.999014
0.001521 -0.043737 0.999042
0.001776 -0.043748 0.999041
0.005639 -0.044047 0.999014
0.001776 -0.043748 0.999041
0.005840 -0.044067 0.999012
0.046003 -0.998941 -0.000008
0.161065 -0.986799 0.016905
0.161065 -0.986799 0.016905
0.161065 -0.986799 0.016905
0.046003 -0.998941 -0.000008
0.046003 -0.998941 -0.000008
0.005639 -0.044047 0.999014
0.008395 -0.044327 0.998982
0.008395 -0.044327 0.998982
0.008395 -0.044327 0.998982
0.005639 -0.044047 0.999014
0.005840 -0.044067 0.999012
0.229390 -0.972750 0.033728
0.161065 -0.986799 0.016905
0.229390 -0.972750 0.033728
0.161065 -0.986799 0.016905
0.229390 -0.972750 0.033728
0.161065 -0.986799 0.016905
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.001521 -0.043737 0.999042
-0.000005 -0.043674 0.999046
-0.000005 -0.043674 0.999046
0.001521 -0.043737 0.999042
-0.000005 -0.043674 0.999046
0.001776 -0.043748 0.999041
0.000000 -1.000000 -0.000010
0.046003 -0.998941 -0.000008
0.046003 -0.998941 -0.000008
0.046003 -0.998941 -0.000008
0.000000 -1.000000 -0.000010
0.000000 -1.000000 -0.000010
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
0.000000 0.000000 -1.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
1.000000 0.000000 0.000000
-0.000000 1.000000 -0.000004
0.000000 1.000000 -0.000003
-0.000000 1.000000 -0.000004
0.000000 1.000000 -0.000003
-0.000000 1.000000 -0.000004
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000001
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000001
0.000000 1.000000 -0.000003
0.000000 1.000000 -0.000001
0.000000 1.000000 -0.000001
0.000000 1.000000 0.000000
0.000000 1.000000 -0.000001
0.000000 1.000000 0.000000
0.000000 1.000000 -0.000001
0.000000 1.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
-1.000000 0.000000 0.000000
</float_array>
<technique_common>
<accessor source="#elevator_right-Normal0-array" count="84" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="elevator_right-UV0">
<float_array id="elevator_right-UV0-array" count="48">
0.250000 0.000000
0.750000 0.000000
0.750000 0.000000
0.750000 1.000000
0.125000 0.000000
0.875000 0.000000
0.875000 0.000000
0.875000 1.000000
0.250000 0.247131
0.750000 0.172769
0.125000 0.234707
0.875000 0.160663
0.556720 0.000000
0.556720 1.000000
0.443280 0.000000
0.556720 0.000000
0.441864 0.247131
0.558584 0.173020
0.897586 0.000000
0.102414 0.000000
0.898211 0.000000
0.898211 1.000000
0.095974 0.232439
0.905697 0.154750
</float_array>
<technique_common>
<accessor source="#elevator_right-UV0-array" count="24" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="elevator_right-VERTEX">
<input semantic="POSITION" source="#elevator_right-POSITION"/>
</vertices>
<triangles count="28" material="FBXASC0481FBXASC032-FBXASC032Default">
<input semantic="VERTEX" offset="0" source="#elevator_right-VERTEX"/>
<input semantic="NORMAL" offset="1" source="#elevator_right-Normal0"/>
<input semantic="TEXCOORD" offset="2" set="0" source="#elevator_right-UV0"/>
<p> 7 0 11 5 1 9 1 2 2 7 3 11 1 4 2 3 5 6 1 6 3 2 7 5 3 8 7 2 9 5 1 10 3 0 11 1 7 12 11 13 13 20 15 14 23 13 15 20 7 16 11 3 17 6 13 18 21 2 19 5 12 20 18 2 21 5 13 22 21 3 23 7 9 24 14 4 25 8 0 26 0 4 27 8 9 28 14 10 29 16 0 30 0 6 31 10 2 32 4 6 33 10 0 34 0 4 35 8 5 36 9 11 37 17 8 38 12 5 39 9 8 40 12 1 41 2 8 42 13 0 43 1 1 44 3 0 45 1 8 46 13 9 47 15 2 48 4 6 49 10 12 50 19 12 51 19 6 52 10 14 53 22 12 54 12 14 55 14 13 56 13 15 57 15 13 58 13 14 59 14 14 60 14 6 61 6 15 62 15 7 63 7 15 64 15 6 65 6 6 66 6 4 67 4 7 68 7 5 69 5 7 70 7 4 71 4 4 72 4 10 73 10 5 74 5 11 75 11 5 76 5 10 77 10 10 78 10 8 79 8 11 80 11 8 81 8 10 82 10 9 83 9</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="elevator_right" name="elevator_right">
<node name="elevator_right" id="elevator_right" sid="elevator_right">
<matrix sid="matrix">0.280290 0.000000 0.000000 0.000000 0.000000 0.280290 0.000000 0.000000 0.000000 0.000000 0.477438 0.000000 0.000000 0.000000 0.000000 1.000000</matrix>
<instance_geometry url="#elevator_right-lib">
<bind_material>
<technique_common>
<instance_material symbol="FBXASC0481FBXASC032-FBXASC032Default" target="#FBXASC0481FBXASC032-FBXASC032Default"/>
</technique_common>
</bind_material>
</instance_geometry>
<extra>
<technique profile="FCOLLADA">
<visibility>1.000000</visibility>
</technique>
</extra>
</node>
<extra>
<technique profile="MAX3D">
<frame_rate>30.000000</frame_rate>
</technique>
<technique profile="FCOLLADA">
<start_time>0.000000</start_time>
<end_time>3.333333</end_time>
</technique>
</extra>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#elevator_right"/>
</scene>
</COLLADA>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,308 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author/>
<authoring_tool>FBX COLLADA exporter</authoring_tool>
<comments/>
</contributor>
<created>2023-01-04T01:05:22Z</created>
<keywords/>
<modified>2023-01-04T01:05:22Z</modified>
<revision/>
<subject/>
<title/>
<unit meter="0.010000" name="centimeter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_materials>
<material id="FBXASC0481FBXASC032-FBXASC032Default" name="FBXASC0481FBXASC032-FBXASC032Default">
<instance_effect url="#FBXASC0481FBXASC032-FBXASC032Default-fx"/>
</material>
</library_materials>
<library_effects>
<effect id="FBXASC0481FBXASC032-FBXASC032Default-fx" name="FBXASC0481FBXASC032-FBXASC032Default">
<profile_COMMON>
<technique sid="standard">
<phong>
<emission>
<color sid="emission">0.000000 0.000000 0.000000 1.000000</color>
</emission>
<ambient>
<color sid="ambient">0.588235 0.588235 0.588235 1.000000</color>
</ambient>
<diffuse>
<color sid="diffuse">0.588235 0.588235 0.588235 1.000000</color>
</diffuse>
<specular>
<color sid="specular">0.486000 0.486000 0.486000 1.000000</color>
</specular>
<shininess>
<float sid="shininess">2.000000</float>
</shininess>
<reflective>
<color sid="reflective">0.000000 0.000000 0.000000 1.000000</color>
</reflective>
<reflectivity>
<float sid="reflectivity">1.000000</float>
</reflectivity>
<transparent opaque="RGB_ZERO">
<color sid="transparent">1.000000 1.000000 1.000000 1.000000</color>
</transparent>
<transparency>
<float sid="transparency">0.000000</float>
</transparency>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_geometries>
<geometry id="Object004-lib" name="Object004Mesh">
<mesh>
<source id="Object004-POSITION">
<float_array id="Object004-POSITION-array" count="66">
17.816429 -14.408081 0.000001
17.816437 -14.408085 0.364992
31.264969 -14.233356 0.000001
31.264977 -14.233356 0.364992
31.264977 -14.233334 0.364993
17.816437 -14.408085 -0.364990
31.264977 -14.233356 -0.364990
31.264977 -14.233334 -0.364991
35.158424 -13.976414 0.000001
35.158417 -13.975285 0.364992
35.158424 -13.975285 -0.364990
-35.158421 -14.408077 0.364992
-35.158421 -14.408077 0.000001
-35.158419 -14.408077 -0.364990
14.887794 1.107790 1.268170
28.354027 1.107794 1.262715
14.887794 1.107794 -1.268169
28.354027 1.107794 -1.262714
35.158417 1.107790 1.254354
35.158440 1.107790 -1.254353
-35.158417 1.107792 1.267323
-35.158417 1.107792 -1.267322
</float_array>
<technique_common>
<accessor source="#Object004-POSITION-array" count="22" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Object004-Normal0">
<float_array id="Object004-Normal0-array" count="342">
0.000320 -0.058124 0.998309
0.001385 -0.058292 0.998299
0.001289 -0.058275 0.998300
0.001385 -0.058292 0.998299
0.000320 -0.058124 0.998309
0.001364 -0.058288 0.998299
0.001289 -0.058275 0.998300
0.000251 -0.058116 0.998310
0.000320 -0.058124 0.998309
0.006496 -0.999979 -0.000005
0.039506 -0.999219 0.000000
0.039507 -0.999219 0.000769
0.039506 -0.999219 0.000000
0.006496 -0.999979 -0.000005
0.006496 -0.999979 -0.000000
0.065994 -0.997819 0.001543
0.039506 -0.999219 0.000000
0.065994 -0.997820 0.000000
0.039506 -0.999219 0.000000
0.065994 -0.997819 0.001543
0.039507 -0.999219 0.000769
0.001385 -0.058292 -0.998299
0.000320 -0.058124 -0.998309
0.001289 -0.058275 -0.998300
0.000320 -0.058124 -0.998309
0.000251 -0.058116 -0.998310
0.001289 -0.058275 -0.998300
0.001364 -0.058288 -0.998299
0.000320 -0.058124 -0.998309
0.001385 -0.058292 -0.998299
0.039506 -0.999219 0.000000
0.006496 -0.999979 -0.000000
0.006496 -0.999979 0.000005
0.039506 -0.999219 0.000000
0.006496 -0.999979 0.000005
0.039507 -0.999219 -0.000769
0.065994 -0.997820 0.000000
0.039506 -0.999219 0.000000
0.039507 -0.999219 -0.000769
0.065994 -0.997820 0.000000
0.039507 -0.999219 -0.000769
0.065994 -0.997819 -0.001543
0.001385 -0.058292 -0.998299
0.002190 -0.058429 -0.998289
0.002190 -0.058429 -0.998289
0.002190 -0.058429 -0.998289
0.001364 -0.058288 -0.998299
0.001385 -0.058292 -0.998299
0.002190 -0.058429 -0.998289
0.001385 -0.058292 -0.998299
0.001289 -0.058275 -0.998300
0.000251 -0.058116 0.998310
-0.000008 -0.058085 0.998312
-0.000008 -0.058085 0.998312
0.000251 -0.058116 0.998310
-0.000008 -0.058085 0.998312
0.000320 -0.058124 0.998309
-0.000000 -1.000000 -0.000005
0.006496 -0.999979 -0.000000
0.006496 -0.999979 -0.000005
0.006496 -0.999979 -0.000000
-0.000000 -1.000000 -0.000005
-0.000000 -1.000000 -0.000000
0.006496 -0.999979 -0.000000
-0.000000 -1.000000 0.000005
0.006496 -0.999979 0.000005
-0.000000 -1.000000 0.000005
0.006496 -0.999979 -0.000000
-0.000000 -1.000000 -0.000000
0.002190 -0.058429 0.998289
0.001385 -0.058292 0.998299
0.002190 -0.058429 0.998289
0.001364 -0.058288 0.998299
0.002190 -0.058429 0.998289
0.001385 -0.058292 0.998299
0.001385 -0.058292 0.998299
0.002190 -0.058429 0.998289
0.001289 -0.058275 0.998300
-0.000008 -0.058085 -0.998312
0.000251 -0.058116 -0.998310
0.000320 -0.058124 -0.998309
0.000251 -0.058116 -0.998310
-0.000008 -0.058085 -0.998312
-0.000008 -0.058085 -0.998312
1.000000 -0.000001 0.000009
1.000000 -0.000001 0.000009
1.000000 -0.000001 0.000009
1.000000 -0.000001 0.000009
1.000000 -0.000001 0.000009
1.000000 -0.000001 0.000009
0.000001 1.000000 0.000000
0.000000 1.000000 0.000000
0.000001 1.000000 0.000000
0.000000 1.000000 0.000000
0.000001 1.000000 0.000000
0.000000 1.000000 0.000000
0.000000 1.000000 0.000000
-0.000000 1.000000 0.000001
0.000000 1.000000 0.000000
-0.000000 1.000000 0.000001
0.000000 1.000000 0.000000
-0.000000 1.000000 0.000001
-0.000000 1.000000 0.000001
0.000000 1.000000 0.000001
-0.000000 1.000000 0.000001
0.000000 1.000000 0.000001
-0.000000 1.000000 0.000001
0.000000 1.000000 0.000001
-1.000000 0.000000 -0.000001
-1.000000 0.000000 -0.000001
-1.000000 0.000000 -0.000001
-1.000000 0.000000 -0.000001
-1.000000 0.000000 -0.000001
-1.000000 0.000000 -0.000001
</float_array>
<technique_common>
<accessor source="#Object004-Normal0-array" count="114" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Object004-UV0">
<float_array id="Object004-UV0-array" count="68">
0.750000 0.000000
0.750000 0.000000
0.750000 1.000000
0.875000 0.000000
0.875000 0.000000
0.875000 1.000000
0.875000 0.000000
0.750000 0.000000
0.750000 0.000000
0.750000 1.000000
0.875000 0.000000
0.875000 0.000000
0.875000 0.000000
0.875000 1.000000
0.897733 0.000000
0.897733 0.000000
0.898362 1.000000
0.898362 0.000000
0.898362 1.000000
0.898362 0.000000
0.557666 0.000000
0.557666 1.000000
0.557666 0.000000
0.557666 0.000000
0.557666 0.000000
0.557666 1.000000
0.750000 0.228410
0.875000 0.222896
0.750000 0.228410
0.875000 0.222896
0.901391 0.229645
0.901391 0.229645
0.560354 0.228679
0.560354 0.228679
</float_array>
<technique_common>
<accessor source="#Object004-UV0-array" count="34" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Object004-VERTEX">
<input semantic="POSITION" source="#Object004-POSITION"/>
</vertices>
<triangles count="38" material="FBXASC0481FBXASC032-FBXASC032Default">
<input semantic="VERTEX" offset="0" source="#Object004-VERTEX"/>
<input semantic="NORMAL" offset="1" source="#Object004-Normal0"/>
<input semantic="TEXCOORD" offset="2" set="0" source="#Object004-UV0"/>
<p> 1 0 1 4 1 6 15 2 27 4 3 6 1 4 1 3 5 4 15 6 27 14 7 26 1 8 1 1 9 2 2 10 3 3 11 5 2 12 3 1 13 2 0 14 0 9 15 16 2 16 3 8 17 14 2 18 3 9 19 16 3 20 5 7 21 11 5 22 7 17 23 29 5 24 7 16 25 28 17 26 29 6 27 10 5 28 7 7 29 11 2 30 12 0 31 8 5 32 9 2 33 12 5 34 9 6 35 13 8 36 15 2 37 12 6 38 13 8 39 15 6 40 13 10 41 18 7 42 11 19 43 31 10 44 19 10 45 19 6 46 10 7 47 11 19 48 31 7 49 11 17 50 29 14 51 26 20 52 32 11 53 20 14 54 26 11 55 20 1 56 1 11 57 21 0 58 0 1 59 2 0 60 0 11 61 21 12 62 22 0 63 8 13 64 25 5 65 9 13 66 25 0 67 8 12 68 23 18 69 30 4 70 6 9 71 17 3 72 4 9 73 17 4 74 6 4 75 6 18 76 30 15 77 27 13 78 24 16 79 28 5 80 7 16 81 28 13 82 24 21 83 33 10 84 10 19 85 19 9 86 9 18 87 18 9 88 9 19 89 19 19 90 19 17 91 17 18 92 18 15 93 15 18 94 18 17 95 17 17 96 17 14 97 14 15 98 15 14 99 14 17 100 17 16 101 16 16 102 16 21 103 21 14 104 14 20 105 20 14 106 14 21 107 21 21 108 21 11 109 11 20 110 20 11 111 11 21 112 21 13 113 13</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="Object004" name="Object004">
<node name="Object004" id="Object004" sid="Object004">
<matrix sid="matrix">-0.000000 0.000000 0.287929 0.000000 0.000000 0.280290 -0.000000 0.000000 0.280290 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000</matrix>
<instance_geometry url="#Object004-lib">
<bind_material>
<technique_common>
<instance_material symbol="FBXASC0481FBXASC032-FBXASC032Default" target="#FBXASC0481FBXASC032-FBXASC032Default"/>
</technique_common>
</bind_material>
</instance_geometry>
<extra>
<technique profile="FCOLLADA">
<visibility>1.000000</visibility>
</technique>
</extra>
</node>
<extra>
<technique profile="MAX3D">
<frame_rate>30.000000</frame_rate>
</technique>
<technique profile="FCOLLADA">
<start_time>0.000000</start_time>
<end_time>3.333333</end_time>
</technique>
</extra>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Object004"/>
</scene>
</COLLADA>

View File

@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>foxtech_loong_2160</name>
<version>1.0</version>
<sdf version='1.9'>model.sdf</sdf>
<author>
<name>Alejandro Hernandez Cordero</name>
<email>alejandro@OpenRobotics.org</email>
</author>
<description>
This is a model of a VTOL.
</description>
</model>

View File

@ -0,0 +1,789 @@
<?xml version="1.0"?>
<sdf version="1.9">
<model name="foxtech">
<link name="base_link">
<visual name="visual_base_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/VTOL.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision_base_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/VTOL.dae</uri>
</mesh>
</geometry>
</collision>
<inertial>
<pose>5.5496318928189852e-08 -0.13220957545547668 0.04102677817672417 1.5707963267949001 -1.5231416921301011 1.5707963267948919</pose>
<mass>3.584838964525901</mass>
<inertia>
<ixx>0.67738485351961117</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.40350427325261343</iyy>
<iyz>0</iyz>
<izz>0.28925142846350795</izz>
</inertia>
</inertial>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
</link>
<link name="airspeed">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.01</radius>
<length>0.1</length>
</cylinder>
</geometry>
<material>
<ambient>0 0 0 1.0</ambient>
<diffuse>0 0 0 1.0</diffuse>
</material>
</visual>
<sensor name="air_speed" type="air_speed">
<always_on>1</always_on>
<update_rate>30</update_rate>
<air_speed>
<airspeed>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</airspeed>
</air_speed>
</sensor>
</link>
<joint name='airspeed_joint' type='fixed'>
<child>airspeed</child>
<parent>base_link</parent>
</joint>
<link name="aileron_left_link">
<pose>-0.713 -0.122 0.062 0 0 0</pose>
<visual name="visual_aileron_left_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/aileron_left.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision_aileron_left_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/aileron_left.dae</uri>
</mesh>
</geometry>
</collision>
<inertial>
<pose>0.016428520956860652 -0.026006344294799606 -0.0023574007803185606 -1.5395303459623877 -1.5044452951949348 -1.6400967799666224</pose>
<mass>0.48889497715279695</mass>
<inertia>
<ixx>0.0046714785213929121</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0044549919806967505</iyy>
<iyz>0</iyz>
<izz>0.00022471747503113157</izz>
</inertia>
</inertial>
</link>
<joint name="servo_0" type="revolute">
<parent>base_link</parent>
<child>aileron_left_link</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="aileron_right_link">
<pose>0.713 -0.122 0.062 0 0 0</pose>
<visual name="visual_aileron_right_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/aileron_right.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision_aileron_right_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/aileron_right.dae</uri>
</mesh>
</geometry>
</collision>
<inertial>
<pose>-0.016428520373255796 -0.026006344259039589 -0.0023573984798765397 -1.6020624043352432 -1.5044453783967096 -1.5014957739781367</pose>
<mass>0.48889496879062661</mass>
<inertia>
<ixx>0.0046714784977765411</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0044549919610427299</iyy>
<iyz>0</iyz>
<izz>0.00022471747055809963</izz>
</inertia>
</inertial>
</link>
<joint name="servo_1" type="revolute">
<parent>base_link</parent>
<child>aileron_right_link</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="elevator_right_link">
<pose>0.145 -0.883 0.058 0 0 0</pose>
<visual name="visual_elevator_right_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/elevator_right.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision_elevator_right_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/elevator_right.dae</uri>
</mesh>
</geometry>
</collision>
<inertial>
<pose>-0.0016067211671852988 -0.018030442713651468 -0.00069522433005383619 -1.5781803398819152 -1.5333187237477242 -1.557643721247719</pose>
<mass>0.060753042156032153</mass>
<inertia>
<ixx>0.00020350509255462549</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00019480985651122032</iyy>
<iyz>0</iyz>
<izz>8.8355306524910641e-06</izz>
</inertia>
</inertial>
</link>
<joint name="servo_2" type="revolute">
<parent>base_link</parent>
<child>elevator_right_link</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="elevator_left_link">
<pose>-0.145 -0.883 0.058 0 0 0</pose>
<visual name="visual_elevator_left_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/elevator_left.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision_elevator_left_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/elevator_left.dae</uri>
</mesh>
</geometry>
</collision>
<inertial>
<pose>0.0016067211849514255 -0.01803044297097545 -0.00069522588918623891 -1.5634123386853667 -1.5333186393334697 -1.5839489042016495</pose>
<mass>0.060753043945841481</mass>
<inertia>
<ixx>0.00020350510004415204</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00019480986370137352</iyy>
<iyz>0</iyz>
<izz>8.8355309624774113e-06</izz>
</inertia>
</inertial>
</link>
<joint name="servo_3" type="revolute">
<parent>base_link</parent>
<child>elevator_left_link</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rudder_link">
<pose>0 -0.887 0.201 0 0 0</pose>
<visual name="visual_rudder_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/rudder.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision_rudder_link">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/rudder.dae</uri>
</mesh>
</geometry>
</collision>
<inertial>
<pose>3.0720176589210631e-09 -0.014597633583934367 -0.00023793299837082617 -0.00096325055376496349 0 0</pose>
<mass>0.08686124232617691</mass>
<inertia>
<ixx>0.00029239473616759126</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00028035840542611708</iyy>
<iyz>0</iyz>
<izz>1.2453403617197103e-05</izz>
</inertia>
</inertial>
</link>
<joint name="servo_4" type="revolute">
<parent>base_link</parent>
<child>rudder_link</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_0">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>0.427 0.403 0.083 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_0_visual">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/propeller_ccw.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_0_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_0_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_0</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_1">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>-0.427 -0.403 0.083 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_1_visual">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/propeller_ccw.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_1_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_1_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_1</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_2">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>-0.427 0.403 0.083 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_2_visual">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/propeller_cw.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_2_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_2_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_2</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="rotor_3">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>0.427 -0.403 0.083 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_3_visual">
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/propeller_cw.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_3_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_3_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_3</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='rotor_puller'>
<pose>0.0 0.379 0.0 -1.57 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_puller_collision'>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_puller_visual'>
<geometry>
<mesh>
<uri>model://foxtech_loong_2160/meshes/propeller_cw.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_puller_joint' type='revolute'>
<child>rotor_puller</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>3500</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.01</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>4</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.05 0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_0</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.05 -0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_1</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>-0.2</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0</cp>
<area>0.01</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.0</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0.</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0.05</cp>
<area>0.02</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 1 0</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_3</control_joint_name>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_3</joint_name>
<sub_topic>servo_3</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.0</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0.</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0.05</cp>
<area>0.02</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 1 0</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_4</control_joint_name>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_4</joint_name>
<sub_topic>servo_4</sub_topic>
</plugin>
</model>
</sdf>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>Standard VTOL</name>
<version>1.0</version>
<sdf version='1.9'>model.sdf</sdf>
<author>
<name>Roman Bapst</name>
<email>roman@px4.io</email>
</author>
<description>
This is a model of a standard VTOL quad plane.
</description>
</model>

View File

@ -0,0 +1,882 @@
<?xml version="1.0"?>
<!-- DO NOT EDIT: Generated from standard_vtol.sdf.jinja -->
<sdf version='1.5'>
<model name='standard_vtol'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>5</mass>
<inertia>
<ixx>0.477708333333</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.341666666667</iyy>
<iyz>0</iyz>
<izz>0.811041666667</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 -0.07 0 0 0</pose>
<geometry>
<box>
<size>0.55 2.144 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1.0</kd>
<max_vel>0.1</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_visual'>
<pose>0.53 -1.072 -0.1 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_wing.dae</uri>
</mesh>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='left_motor_column'>
<pose>0 0.35 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.74 0.03 0.03</size>
</box>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='right_motor_column'>
<pose>0 -0.35 0.01 0 0 0</pose>
<geometry>
<box>
<size>0.74 0.03 0.03</size>
</box>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m0'>
<pose>-0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m1'>
<pose>-0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m2'>
<pose>0.35 -0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<visual name='m3'>
<pose>0.35 0.35 0.045 0 0 0</pose>
<geometry>
<cylinder>
<length>0.035</length>
<radius>0.02</radius>
</cylinder>
</geometry>
<material>
<ambient>.175 .175 .175 1.0</ambient>
<diffuse>.175 .175 .175 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
</link>
<link name="airspeed">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.01</radius>
<length>0.1</length>
</cylinder>
</geometry>
<material>
<ambient>0 0 0 1.0</ambient>
<diffuse>0 0 0 1.0</diffuse>
</material>
</visual>
<sensor name="air_speed" type="air_speed">
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<enable_metrics>true</enable_metrics>
<air_speed>
<airspeed>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</airspeed>
</air_speed>
</sensor>
</link>
<joint name='airspeed_joint' type='fixed'>
<child>airspeed</child>
<parent>base_link</parent>
</joint>
<!-- <include>
<uri>model://airspeed</uri>
<pose>0 0 0 0 0 0</pose>
<name>airspeed</name>
</include>
<include>
<uri>model://magnetometer</uri>
<pose>0 0 0 0 0 0</pose>
<name>mag</name>
</include>
<joint name='mag_joint' type='fixed'>
<child>mag::link</child>
<parent>base_link</parent>
</joint> -->
<link name='rotor_0'>
<pose>0.35 -0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_0_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_0_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_1'>
<pose>-0.35 0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_1_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_1_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_2'>
<pose>0.35 0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_2_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_2_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_3'>
<pose>-0.35 -0.35 0.07 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_puller'>
<pose>-0.22 0 0.0 0 1.57 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000166704</iyy>
<iyz>0</iyz>
<izz>0.000167604</izz>
</inertia>
</inertial>
<collision name='rotor_puller_collision'>
<pose>0.0 0 -0.04 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.06</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_puller_visual'>
<pose>0 0 -0.04 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8 0.8 0.8</scale>
<uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<joint name='rotor_puller_joint' type='revolute'>
<child>rotor_puller</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="left_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 0.3 0 0.00 0 0.0</pose>
</inertial>
<visual name='left_elevon_visual'>
<pose>-0.105 0.004 -0.034 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_elevon_left.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="right_elevon">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>0 -0.6 0 0.00 0 0.0</pose>
</inertial>
<visual name='right_elevon_visual'>
<pose>0.281 -1.032 -0.034 1.5707963268 0 3.1415926536</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://standard_vtol/meshes/x8_elevon_right.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1.0</ambient>
<diffuse>0 0 1 1.0</diffuse>
</material>
</visual>
</link>
<link name="elevator">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose> -0.5 0 0 0.00 0 0.0</pose>
</inertial>
</link>
<link name="rudder">
<inertial>
<mass>0.00000001</mass>
<inertia>
<ixx>0.000001</ixx>
<ixy>0.0</ixy>
<iyy>0.000001</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.000001</izz>
</inertia>
<pose>-0.5 0 0.05 0 0 0 </pose>
</inertial>
</link>
<joint name='servo_0' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<pose>-0.18 0.6 -0.005 0 0 0.265</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_1' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<pose>-0.18 -0.6 -0.005 0 0 -0.265</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_2' type='revolute'>
<parent>base_link</parent>
<child>elevator</child>
<pose> -0.5 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<joint name='servo_3' type='revolute'>
<parent>base_link</parent>
<child>rudder</child>
<pose>-0.5 0 0.05 0.00 0 0.0</pose>
<axis>
<xyz>1 0 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.01</lower>
<upper>0.01</upper>
</limit>
<dynamics>
<damping>1.000</damping>
</dynamics>
</axis>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
</joint>
<!-- <include>
<uri>model://gps</uri>
<pose>0 0 0 0 0 0</pose>
<name>gps</name>
</include>
<joint name='gps_joint' type='fixed'>
<child>gps::link</child>
<parent>base_link</parent>
</joint> -->
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<!-- <plugin name="left_wing_lift" filename="libLiftDragPlugin.so"> -->
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.05 0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_0</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
</plugin>
<!-- <plugin name="right_wing_lift" filename="libLiftDragPlugin.so"> -->
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.05 -0.3 0.05</cp>
<area>0.50</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_1</control_joint_name>
<control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
</plugin>
<!-- <plugin name="elevator_lift" filename="libLiftDragPlugin.so"> -->
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>-0.2</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0</cp>
<area>0.01</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
</plugin>
<!-- <plugin name="rudder_lift" filename="libLiftDragPlugin.so"> -->
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.0</a0>
<cla>4.752798721</cla>
<cda>0.6417112299</cda>
<cma>0.0.</cma>
<alpha_stall>0.3391428111</alpha_stall>
<cla_stall>-3.85</cla_stall>
<cda_stall>-0.9233984055</cda_stall>
<cma_stall>0</cma_stall>
<cp>-0.5 0 0.05</cp>
<area>0.02</area>
<air_density>1.2041</air_density>
<forward>1 0 0</forward>
<upward>0 1 0</upward>
<link_name>base_link</link_name>
<control_joint_name>servo_3</control_joint_name>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>servo_3</joint_name>
<sub_topic>servo_3</sub_topic>
</plugin>
<!-- <plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>2e-05</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<!-- <plugin name='puller_motor_model' filename='libgazebo_motor_model.so'> -->
<plugin
filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>3500</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.01</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>4</motorNumber>
<rotorDragCoefficient>0.000106428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<static>0</static>
</model>
</sdf>