5 - All rotation about Z-Axis
6 - Gripper base at offset from last link
7 - Gripper base points to Z-Direction
10 <robot name="arm" xmlns:xacro="http://ros.org/wiki/xacro">
11 <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
13 <link name="base_link">
19 <mesh filename="package://arm_ros_conn/meshes/32985.stl"/>
21 <material name="black">
22 <color rgba="0 0 0 1"/>
27 <link name="arm_base">
33 <mesh filename="package://arm_ros_conn/meshes/link1.stl"/>
35 <origin xyz="0 0 0.0615"/>
36 <material name="grey">
37 <color rgba="0.5 0.5 0.5 1"/>
45 <mesh filename="package://arm_ros_conn/meshes/link2.stl"/>
47 <origin xyz="0.120 0 0" rpy="1.5708 0 1.5708"/>
48 <material name="grey">
49 <color rgba="0.5 0.5 0.5 1"/>
57 <mesh filename="package://arm_ros_conn/meshes/link3.stl"/>
59 <origin xyz="0 0.0675 0" rpy="1.5708 0 0"/>
60 <material name="grey">
61 <color rgba="0.5 0.5 0.5 1"/>
69 <mesh filename="package://arm_ros_conn/meshes/link4.stl"/>
71 <origin xyz="0 0 0.015" rpy="0 0 0"/>
72 <material name="black">
73 <color rgba="0 0 0 1"/>
81 <mesh filename="package://arm_ros_conn/meshes/31019.stl"/>
83 <origin xyz="0.0 0 0" rpy="0 0 0"/>
85 <color rgba="1 0 0 1"/>
90 <link name="gripper_pole">
93 <link name="gripper_center">
96 <link name="left_gripper">
98 <origin xyz="0.025 0 0" rpy="-1.5708 3.1416 0"/>
100 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
102 <material name="red">
103 <color rgba="1 0 0 1"/>
108 <link name="right_gripper">
110 <origin xyz="0.025 0 0" rpy="-1.5708 3.1416 0"/>
112 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
114 <material name="red">
115 <color rgba="1 0 0 1"/>
120 <link name="link2_motor_extension">
123 <box size="0.015 0.015 0.10"/>
125 <origin xyz="0 0 0.05" rpy="0 0 0"/>
126 <material name="grey">
127 <color rgba="0.5 0.5 0.5 1"/>
132 <link name="plate_box">
135 <box size="0.08 0.185 0.035"/>
137 <origin xyz="0 0 0.0175" rpy="0 0 0"/>
138 <material name="black">
139 <color rgba="0 0 0 1"/>
144 <joint name="plate_joint" type="fixed">
145 <parent link="base_link"/>
146 <child link="plate"/>
147 <origin xyz="0 0 0.00375"/>
150 <joint name="arm_base_joint" type="fixed">
151 <parent link="plate"/>
152 <child link="arm_base"/>
153 <origin xyz="0 0.099 0"/>
156 <joint name="link1_joint" type="revolute">
157 <parent link="arm_base"/>
158 <child link="link1"/>
160 <limit effort="1.0" lower="0.0" upper="5.672320068981571" velocity="0.2"/>
163 <joint name="link2_joint" type="revolute">
164 <parent link="link1"/>
165 <child link="link2"/>
167 <origin xyz="0.0 0.0 0.123" rpy="1.5708 0 0"/>
168 <limit effort="1.0" lower="0.1505" upper="3.611" velocity="0.1"/>
171 <joint name="link3_joint" type="revolute">
172 <parent link="link2"/>
173 <child link="link3"/>
175 <origin xyz="0.240 0 0" rpy="0 0 0"/>
176 <limit effort="1.0" lower="0" upper="3.1416" velocity="0.2"/>
179 <joint name="link4_joint" type="revolute">
180 <parent link="link3"/>
181 <child link="link4"/>
183 <origin xyz="0 0.135 0" rpy="-1.5708 0 0"/>
184 <limit effort="1.0" lower="-0.15708" upper="5.4978" velocity="0.5"/>
187 <joint name="link5_joint" type="revolute">
188 <parent link="link4"/>
189 <child link="link5"/>
191 <origin xyz="0 0 0.06" rpy="1.5708 0 0"/>
192 <limit effort="1.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
195 <joint name="gripper_pole_joint" type="fixed">
196 <parent link="link5"/>
197 <child link="gripper_pole"/>
198 <origin xyz="0 0.02275 0" rpy="1.5708 0 1.5708"/>
201 <joint name="gripper_center_joint" type="fixed">
202 <parent link="gripper_pole"/>
203 <child link="gripper_center"/>
204 <origin xyz="0.08 0 0" rpy="0 0 0"/>
207 <joint name="left_gripper_joint" type="revolute">
208 <parent link="gripper_pole"/>
209 <child link="left_gripper"/>
211 <origin xyz="0 0.015 0" rpy="0 0 0"/>
212 <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
215 <joint name="right_gripper_joint" type="revolute">
216 <parent link="gripper_pole"/>
217 <child link="right_gripper"/>
219 <origin xyz="0 -0.015 0" rpy="3.1416 0 0"/>
220 <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
223 <joint name="link2_motor_extension_joint" type="fixed">
224 <parent link="link2"/>
225 <child link="link2_motor_extension"/>
226 <origin xyz="0.165 -0.03 0" rpy="1.5708 0 0"/>
229 <joint name="plate_box_joint" type="fixed">
230 <parent link="plate"/>
231 <child link="plate_box"/>
232 <origin xyz="-0.04 -0.035 0" rpy="0 0 0"/>
235 <xacro:asus_camera name="camera" parent="link2">
236 <origin xyz="0.18 -0.03 -0.05" rpy="0 3.1416 -1.5708"/>