5 - All rotation about Z-Axis
6 - Gripper base at offset from last link
7 - Gripper base points to Z-Direction
11 <link name="base_link">
17 <mesh filename="package://arm_ros_conn/meshes/32985.stl"/>
19 <material name="black">
20 <color rgba="0 0 0 1"/>
25 <link name="arm_base">
31 <mesh filename="package://arm_ros_conn/meshes/link1.stl"/>
33 <origin xyz="0 0 0.0615"/>
34 <material name="grey">
35 <color rgba="0.5 0.5 0.5 1"/>
43 <mesh filename="package://arm_ros_conn/meshes/link2.stl"/>
45 <origin xyz="0.120 0 0" rpy="1.5708 0 1.5708"/>
46 <material name="grey">
47 <color rgba="0.5 0.5 0.5 1"/>
55 <mesh filename="package://arm_ros_conn/meshes/link3.stl"/>
57 <origin xyz="0 0.0675 0" rpy="1.5708 0 0"/>
58 <material name="grey">
59 <color rgba="0.5 0.5 0.5 1"/>
67 <mesh filename="package://arm_ros_conn/meshes/link4.stl"/>
69 <origin xyz="0 0 0.015" rpy="0 0 0"/>
70 <material name="black">
71 <color rgba="0 0 0 1"/>
79 <mesh filename="package://arm_ros_conn/meshes/31019.stl"/>
81 <origin xyz="0.0 0 0" rpy="0 0 0"/>
83 <color rgba="1 0 0 1"/>
88 <link name="gripper_pole">
91 <link name="gripper_center">
94 <link name="left_gripper">
96 <origin xyz="0.025 0 0" rpy="-1.5708 3.1416 0"/>
98 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
100 <material name="red">
101 <color rgba="1 0 0 1"/>
106 <link name="right_gripper">
108 <origin xyz="0.025 0 0" rpy="-1.5708 3.1416 0"/>
110 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
112 <material name="red">
113 <color rgba="1 0 0 1"/>
118 <joint name="plate_joint" type="fixed">
119 <parent link="base_link"/>
120 <child link="plate"/>
121 <origin xyz="0 0 0.00375"/>
124 <joint name="arm_base_joint" type="fixed">
125 <parent link="plate"/>
126 <child link="arm_base"/>
127 <origin xyz="0 0.099 0"/>
130 <joint name="link1_joint" type="revolute">
131 <parent link="arm_base"/>
132 <child link="link1"/>
134 <limit effort="1.0" lower="0.0" upper="5.672320068981571" velocity="1.0"/>
137 <joint name="link2_joint" type="revolute">
138 <parent link="link1"/>
139 <child link="link2"/>
141 <origin xyz="0.0 0.0 0.123" rpy="1.5708 0 0"/>
142 <limit effort="1.0" lower="0.1505" upper="3.611" velocity="1.0"/>
145 <joint name="link3_joint" type="revolute">
146 <parent link="link2"/>
147 <child link="link3"/>
149 <origin xyz="0.240 0 0" rpy="0 0 0"/>
150 <limit effort="1.0" lower="0" upper="3.1416" velocity="1.0"/>
153 <joint name="link4_joint" type="revolute">
154 <parent link="link3"/>
155 <child link="link4"/>
157 <origin xyz="0 0.135 0" rpy="-1.5708 0 0"/>
158 <limit effort="1.0" lower="-0.15708" upper="5.4978" velocity="1.0"/>
161 <joint name="link5_joint" type="revolute">
162 <parent link="link4"/>
163 <child link="link5"/>
165 <origin xyz="0 0 0.06" rpy="1.5708 0 0"/>
166 <limit effort="1.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
169 <joint name="gripper_pole_joint" type="fixed">
170 <parent link="link5"/>
171 <child link="gripper_pole"/>
172 <origin xyz="0 0.02275 0" rpy="1.5708 0 1.5708"/>
175 <joint name="gripper_center_joint" type="fixed">
176 <parent link="gripper_pole"/>
177 <child link="gripper_center"/>
178 <origin xyz="0.08 0 0" rpy="0 0 0"/>
181 <joint name="left_gripper_joint" type="revolute">
182 <parent link="gripper_pole"/>
183 <child link="left_gripper"/>
185 <origin xyz="0 0.015 0" rpy="0 0 0"/>
186 <limit effort="1.0" lower="0.0" upper="0.35" velocity="1.0"/>
189 <joint name="right_gripper_joint" type="revolute">
190 <parent link="gripper_pole"/>
191 <child link="right_gripper"/>
193 <origin xyz="0 -0.015 0" rpy="3.1416 0 0"/>
194 <limit effort="1.0" lower="0.0" upper="0.35" velocity="1.0"/>