3 <link name="base_link">
9 <mesh filename="package://arm_ros_conn/meshes/32985.stl"/>
11 <material name="black">
12 <color rgba="0 0 0 1"/>
17 <link name="arm_base">
23 <mesh filename="package://arm_ros_conn/meshes/link1.stl"/>
25 <origin xyz="0 0 0.0615"/>
26 <material name="grey">
27 <color rgba="0.5 0.5 0.5 1"/>
35 <mesh filename="package://arm_ros_conn/meshes/link2.stl"/>
37 <origin xyz="0 0 0.120" rpy="0 0 0"/>
38 <material name="grey">
39 <color rgba="0.5 0.5 0.5 1"/>
47 <mesh filename="package://arm_ros_conn/meshes/link3.stl"/>
49 <origin xyz="0 0 0.0675" rpy="0 0 0"/>
50 <material name="grey">
51 <color rgba="0.5 0.5 0.5 1"/>
59 <mesh filename="package://arm_ros_conn/meshes/link4.stl"/>
61 <origin xyz="0 0 0.015" rpy="0 0 0"/>
62 <material name="black">
63 <color rgba="0 0 0 1"/>
71 <mesh filename="package://arm_ros_conn/meshes/31019.stl"/>
73 <origin xyz="0.0 0 0" rpy="1.5708 0 0"/>
75 <color rgba="1 0 0 1"/>
80 <link name="gripper_pole">
83 <link name="gripper_center">
86 <link name="left_gripper">
88 <origin xyz="0.025 0 0" rpy="-1.57075 3.1415 0"/>
90 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
93 <color rgba="1 0 0 1"/>
98 <link name="right_gripper">
100 <origin xyz="0.025 0 0" rpy="1.57075 3.1415 0"/>
102 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
104 <material name="red">
105 <color rgba="1 0 0 1"/>
110 <joint name="plate_joint" type="fixed">
111 <parent link="base_link"/>
112 <child link="plate"/>
113 <origin xyz="0 0 0.00375"/>
116 <joint name="arm_base_joint" type="fixed">
117 <parent link="plate"/>
118 <child link="arm_base"/>
119 <origin xyz="0 0.099 0"/>
122 <joint name="link1_joint" type="revolute">
123 <parent link="arm_base"/>
124 <child link="link1"/>
126 <limit effort="1000.0" lower="0.0" upper="5.672320068981571" velocity="1.0"/>
129 <joint name="link2_joint" type="revolute">
130 <parent link="link1"/>
131 <child link="link2"/>
133 <origin xyz="0.0 0.0 0.123" rpy="0 1.5708 0"/>
134 <limit effort="1000.0" lower="0.1505" upper="3.611" velocity="1.0"/>
137 <joint name="link3_joint" type="revolute">
138 <parent link="link2"/>
139 <child link="link3"/>
141 <origin xyz="0 0 0.240" rpy="0 -1.5708 0"/>
142 <limit effort="1000.0" lower="0" upper="3.1416" velocity="1.0"/>
145 <joint name="link4_joint" type="revolute">
146 <parent link="link3"/>
147 <child link="link4"/>
149 <origin xyz="0 0 0.135" rpy="0 0 0"/>
150 <limit effort="1000.0" lower="-0.15708" upper="5.4978" velocity="1.0"/>
153 <joint name="link5_joint" type="revolute">
154 <parent link="link4"/>
155 <child link="link5"/>
157 <origin xyz="0 0 0.06" rpy="0 0 0"/>
158 <limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
161 <joint name="gripper_pole_joint" type="fixed">
162 <parent link="link5"/>
163 <child link="gripper_pole"/>
166 <joint name="gripper_center_joint" type="fixed">
167 <parent link="gripper_pole"/>
168 <child link="gripper_center"/>
169 <origin xyz="0.0 0.0 0.1" rpy="0 0 0" />
172 <joint name="left_gripper_joint" type="revolute">
173 <parent link="gripper_pole"/>
174 <child link="left_gripper"/>
176 <origin xyz="0.0 0.01 0.02" rpy="0 -1.5708 0" />
177 <limit effort="1000.0" lower="0.0" upper="0.35" velocity="1.0"/>
180 <joint name="right_gripper_joint" type="revolute">
181 <parent link="gripper_pole"/>
182 <child link="right_gripper"/>
184 <origin xyz="0.0 -0.01 0.02" rpy="0 -1.5708 0"/>
185 <limit effort="1000.0" lower="0.0" upper="0.35" velocity="1.0"/>