forked from andybarry/simflight
-
Notifications
You must be signed in to change notification settings - Fork 0
/
TBSC_visualizer.urdf
130 lines (115 loc) · 3.32 KB
/
TBSC_visualizer.urdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
<?xml version="1.0"?>
<robot xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="http://drake.mit.edu ../../doc/drakeURDF.xsd" name="TBSC_visualizer">
<link name="fuselage">
<inertial>
<mass value="1" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="0.083" />
</inertial>
<visual>
<geometry>
<box size="0.2097 0.8636 0.01" />
</geometry>
</visual>
</link>
<link name="left_winglet">
<parent link="fuselage" />
<inertial>
<mass value="1" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="0.083" />
</inertial>
<visual>
<geometry>
<origin xyz="-0.08 0.4318 0.081954" rpy="1.57079632679489661923 0 0" />
<box size="0.1303 0.1492 0.01" />
</geometry>
</visual>
</link>
<link name="prop">
<inertial>
<mass value="1" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="0.083" />
</inertial>
<visual>
<geometry>
<origin xyz="-0.15 0 0" rpy="0 1.57079632679489661923 0" />
<cylinder length="0.05" radius="0.1016" />
</geometry>
</visual>
</link>
<link name="right_winglet">
<inertial>
<mass value="1" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="0.083" />
</inertial>
<visual>
<geometry>
<origin xyz="-0.08 -0.4318 0.081954" rpy="1.57079632679489661923 0 0" />
<box size="0.1303 0.1492 0.01" />
</geometry>
</visual>
</link>
<link name="left_elevon">
<inertial>
<mass value="1" />
<origin xyz="-0.0201 0.276225 0" rpy="0 0 0" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="0.083" />
</inertial>
<visual>
<origin xyz="-0.0201 0.276225 0" rpy="0 0 0" />
<geometry>
<box size="0.0402 0.31115 0.01" />
</geometry>
<material name="red">
<color rgba="1 .949 .211 1" />
</material>
</visual>
</link>
<link name="right_elevon">
<inertial>
<mass value="1" />
<origin xyz="-0.0201 -0.276225 0" rpy="0 0 0" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="0.083" />
</inertial>
<visual>
<origin xyz="-0.0201 -0.276225 0" rpy="0 0 0" />
<geometry>
<box size="0.0402 0.31115 0.01" />
</geometry>
<material name="red">
<color rgba="1 .949 .211 1" />
</material>
</visual>
</link>
<joint name="left_elevon_joint" type="continuous">
<parent link="fuselage" />
<child link="left_elevon" />
<origin xyz="-0.10485 0 0" />
<axis xyz="0 1 0" />
</joint>
<joint name="right_elevon_joint" type="continuous">
<parent link="fuselage" />
<child link="right_elevon" />
<origin xyz="-0.10485 0 0" />
<axis xyz="0 1 0" />
</joint>
<joint name="left_winglet_joint" type="fixed">
<parent link="fuselage" />
<child link="left_winglet" />
<origin xyz="0 0 0" />
<axis xyz="0 1 0" />
</joint>
<joint name="right_winglet_joint" type="fixed">
<parent link="fuselage" />
<child link="right_winglet" />
<origin xyz="0 0 0" />
<axis xyz="0 1 0" />
</joint>
<joint name="prop_joint" type="continuous">
<parent link="fuselage" />
<child link="prop" />
<origin xyz="0 0 0" />
<axis xyz="1 0 0" />
</joint>
</robot>