2 <!-- Open_Manipulator Chain -->
3 <robot name="open_manipulator" xmlns:xacro="http://ros.org/wiki/xacro">
5 <!-- Import all Gazebo-customization elements, including Gazebo colors -->
6 <xacro:include filename="$(find open_manipulator_description)/urdf/open_manipulator.gazebo.xacro" />
7 <!-- Import Rviz colors -->
8 <xacro:include filename="$(find open_manipulator_description)/urdf/materials.xacro" />
9 <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>
11 <!-- Transmission macro -->
12 <xacro:macro name="SimpleTransmission" params="joint n">
13 <transmission name="tran${n}">
14 <type>transmission_interface/SimpleTransmission</type>
15 <joint name="${joint}">
16 <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
18 <actuator name="motor${n}">
19 <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
20 <mechanicalReduction>1</mechanicalReduction>
25 <link name="open_manipulator_base">
28 <joint name="world_fixed" type="fixed">
29 <origin xyz="0 0 0" rpy="0 0 0"/>
30 <parent link="open_manipulator_base"/>
37 <origin xyz="0 0 0" rpy="0 0 0"/>
39 <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
41 <material name="grey"/>
45 <origin xyz="0 0 0" rpy="0 0 0"/>
47 <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
52 <origin xyz="0 0 0" />
53 <mass value="0.082" />
54 <inertia ixx="0.1" ixy="0.0" ixz="0.0"
60 <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04" />
61 <mass value="7.9119962e-02" />
62 <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07"
63 iyy="2.1898364e-05" iyz="0.0"
64 izz="1.9267361e-05" />
69 <joint name="joint1" type="revolute">
70 <parent link="link1"/>
72 <origin xyz="0.012 0.0 0.017" rpy="0 0 0"/>
74 <limit velocity="4.8" effort="1" lower="${-pi}" upper="${pi}" />
77 <!-- Transmission 1 -->
78 <xacro:SimpleTransmission n="1" joint="joint1" />
83 <origin xyz="0 0 0.019" rpy="0 0 0"/>
85 <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
87 <material name="grey"/>
91 <origin xyz="0 0 0.019" rpy="0 0 0"/>
93 <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
98 <origin xyz="0 0 0" />
99 <mass value="0.098" />
100 <inertia ixx="0.1" ixy="0.0" ixz="0.0"
106 <origin xyz="-3.0184870e-04 5.4043684e-04 ${0.018 + 2.9433464e-02}" />
107 <mass value="9.8406837e-02" />
108 <inertia ixx="3.4543422e-05" ixy="-1.6031095e-08" ixz="-3.8375155e-07"
109 iyy="3.2689329e-05" iyz="2.8511935e-08"
110 izz="1.8850320e-05" />
115 <joint name="joint2" type="revolute">
116 <parent link="link2"/>
117 <child link="link3"/>
118 <origin xyz="0.0 0.0 0.0595" rpy="0 0 0"/>
120 <limit velocity="4.8" effort="1" lower="${-pi*0.64}" upper="${pi*0.64}" />
123 <!-- Transmission 2 -->
124 <xacro:SimpleTransmission n="2" joint="joint2" />
129 <origin xyz="0 0 0" rpy="0 0 0"/>
131 <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
133 <material name="grey"/>
137 <origin xyz="0 0 0" rpy="0 0 0"/>
139 <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
144 <origin xyz="0 0 0" />
145 <mass value="0.136" />
146 <inertia ixx="0.1" ixy="0.0" ixz="0.0"
152 <origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01" />
153 <mass value="1.3850917e-01" />
154 <inertia ixx="3.3055381e-04" ixy="-9.7940978e-08" ixz="-3.8505711e-05"
155 iyy="3.4290447e-04" iyz="-1.5717516e-06"
156 izz="6.0346498e-05" />
161 <joint name="joint3" type="revolute">
162 <parent link="link3"/>
163 <child link="link4"/>
164 <origin xyz="0.024 0 0.128" rpy="0 0 0"/>
166 <limit velocity="4.8" effort="1" lower="${-pi*0.64}" upper="${pi*0.48}" />
169 <!-- Transmission 3 -->
170 <xacro:SimpleTransmission n="3" joint="joint3" />
175 <origin xyz="0 0 0" rpy="0 0 0"/>
177 <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
179 <material name="grey"/>
183 <origin xyz="0 0 0" rpy="0 0 0"/>
185 <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
190 <origin xyz="0 0 0" />
191 <mass value="0.131" />
192 <inertia ixx="0.1" ixy="0.0" ixz="0.0"
198 <origin xyz="9.0909590e-02 3.8929816e-04 2.2413279e-04" />
199 <mass value="1.3274562e-01" />
200 <inertia ixx="3.0654178e-05" ixy="-1.2764155e-06" ixz="-2.6874417e-07"
201 iyy="2.4230292e-04" iyz="1.1559550e-08"
202 izz="2.5155057e-04" />
207 <joint name="joint4" type="revolute">
208 <parent link="link4"/>
209 <child link="link5"/>
210 <origin xyz="0.124 0.0 0.0" rpy="0 0 0"/>
212 <limit velocity="4.8" effort="1" lower="${-pi*0.57}" upper="${pi*0.65}" />
215 <!-- Transmission 4 -->
216 <xacro:SimpleTransmission n="4" joint="joint4" />
221 <origin xyz="0 0 0" rpy="0 0 0"/>
223 <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
225 <material name="grey"/>
229 <origin xyz="0 0 0" rpy="0 0 0"/>
231 <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
236 <origin xyz="0 0 0" />
237 <mass value="0.141" />
238 <inertia ixx="0.1" ixy="0.0" ixz="0.0"
244 <origin xyz="4.4206755e-02 3.6839985e-07 8.9142216e-03" />
245 <mass value="1.4327573e-01" />
246 <inertia ixx="8.0870749e-05" ixy="0.0" ixz="-1.0157896e-06"
247 iyy="7.5980465e-05" iyz="0.0"
248 izz="9.3127351e-05" />
252 <!-- Gripper link -->
253 <link name="gripper_link">
255 <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
257 <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
259 <material name="grey"/>
263 <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
265 <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
270 <origin xyz="0 0 0" />
271 <mass value="0.017" />
272 <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
273 iyy="1.0e-03" iyz="0.0"
278 <origin xyz="${0.028 + 8.3720668e-03} ${0.0246 + 9.9696160e-03} -4.2836895e-07" />
279 <mass value="3.2218127e-02" />
280 <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
281 iyy="2.2552871e-05" iyz="-3.1463634e-10"
282 izz="1.7605306e-05" />
286 <!-- Gripper joint -->
287 <joint name="gripper" type="prismatic">
288 <parent link="link5"/>
289 <child link="gripper_link"/>
290 <origin xyz="0.0817 0.021 0.0" rpy="0 0 0"/>
292 <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
295 <!-- Transmission 5 -->
296 <xacro:SimpleTransmission n="5" joint="gripper" />
298 <!-- Gripper link sub -->
299 <link name="gripper_link_sub">
301 <origin xyz="0.0 -0.0 0" rpy="0 0 0"/>
303 <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
305 <material name="grey"/>
309 <origin xyz="0.0 -0.0 0" rpy="0 0 0"/>
311 <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
316 <origin xyz="0 0 0" />
317 <mass value="0.017" />
318 <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
319 iyy="1.0e-03" iyz="0.0"
324 <origin xyz="${0.028 + 8.3720668e-03} ${-0.0246 - 9.9696160e-03} -4.2836895e-07" />
325 <mass value="3.2218127e-02" />
326 <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
327 iyy="2.2552871e-05" iyz="-3.1463634e-10"
328 izz="1.7605306e-05" />
332 <!-- Gripper joint sub -->
333 <joint name="gripper_sub" type="prismatic">
334 <parent link="link5"/>
335 <child link="gripper_link_sub"/>
336 <origin xyz="0.0817 -0.021 0" rpy="0 0 0"/>
338 <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
339 <mimic joint="gripper" multiplier="1"/>
342 <!-- Transmission 6 -->
343 <xacro:SimpleTransmission n="6" joint="gripper_sub" />
345 <!-- end effector joint -->
346 <joint name="end_effector_joint" type="fixed">
347 <origin xyz="0.126 0.0 0.0" rpy="0 0 0"/>
348 <parent link="link5"/>
349 <child link="end_effector_link"/>
352 <!-- end effector link -->
353 <link name="end_effector_link">
355 <origin xyz="0 0 0" rpy="0 0 0"/>
357 <box size="0.01 0.01 0.01" />
359 <material name="red"/>
363 <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
364 <mass value="0.001"/>
365 <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06" />
369 <sensor_d435 parent="gripper_link">
370 <origin xyz="-0.02 -0.018 0.055" rpy="0 0 0"/>