3 <link name="base_link">
6 <mesh filename="package://arm_ros_conn/meshes/32985.stl" scale="1 1 1"/>
8 <material name="black">
9 <color rgba="0 0 0 1"/>
17 <box size="0.06 0.03 0.123"/>
19 <origin xyz="0 0 0.0675"/>
20 <material name="grey">
21 <color rgba="0.5 0.5 0.5 1"/>
29 <box size="0.240 0.06 0.03"/>
31 <origin xyz="0.120 0 0.0" rpy="0 0 0"/>
32 <material name="grey">
33 <color rgba="0.5 0.5 0.5 1"/>
41 <box size="0.06 0.135 0.03"/>
43 <origin xyz="0.0 0.0675 0.0" rpy="0 0 0"/>
44 <material name="grey">
45 <color rgba="0.5 0.5 0.5 1"/>
53 <cylinder radius="0.045" length="0.03"/>
55 <origin xyz="0.015 0 0" rpy="0 1.57075 0"/>
56 <material name="black">
57 <color rgba="0 0 0 1"/>
65 <mesh filename="package://arm_ros_conn/meshes/31019.stl" scale="1 1 1"/>
67 <origin xyz="0.0 0 0" rpy="1.57075 0 0"/>
69 <color rgba="1 0 0 1"/>
74 <link name="gripper_pole">
77 <link name="left_gripper">
79 <origin xyz="0.025 0 0" rpy="-1.57075 3.1415 0"/>
81 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
84 <color rgba="1 0 0 1"/>
89 <link name="right_gripper">
91 <origin xyz="0.025 0 0" rpy="1.57075 3.1415 0"/>
93 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
96 <color rgba="1 0 0 1"/>
101 <joint name="base_to_link1" type="continuous">
102 <parent link="base_link"/>
103 <child link="link1"/>
105 <origin xyz="0 0.099 0"/>
106 <limit effort="1000.0" lower="-5.672320068981571" upper="0.0" velocity="1.0"/>
109 <joint name="link_1_2_joint" type="continuous">
110 <parent link="link1"/>
111 <child link="link2"/>
113 <origin xyz="0.0 0.0 0.135" rpy="1.57075 0 0"/>
114 <limit effort="1000.0" lower="0.15045941827537324" upper="3.6110260386089577" velocity="1.0"/>
117 <joint name="link_2_3_joint" type="continuous">
118 <parent link="link2"/>
119 <child link="link3"/>
121 <origin xyz="0.240 0.0 0.0" rpy="0 0 0"/>
122 <limit effort="1000.0" lower="-3.141592653589793" upper="0.0" velocity="1.0"/>
125 <joint name="link_3_4_joint" type="continuous">
126 <parent link="link3"/>
127 <child link="link4"/>
129 <origin xyz="0 0.135 0.0" rpy="1.57075 0 1.57075"/>
130 <limit effort="1000.0" lower="-7.679448708775051" upper="0.6981317007977319" velocity="1.0"/>
133 <joint name="link_4_5_joint" type="continuous">
134 <parent link="link4"/>
135 <child link="link5"/>
137 <origin xyz="0.06 0.0 0.0" rpy="0 0 0"/>
138 <limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
141 <joint name="gripper_pole_joint" type="fixed">
142 <parent link="link5"/>
143 <child link="gripper_pole"/>
146 <joint name="left_gripper_joint" type="revolute">
147 <parent link="gripper_pole"/>
148 <child link="left_gripper"/>
150 <origin xyz="0.02 0.01 0" rpy="0 0 0" />
151 <limit effort="1000.0" lower="0.0" upper="0.35" velocity="1.0"/>
154 <joint name="right_gripper_joint" type="revolute">
155 <parent link="gripper_pole"/>
156 <child link="right_gripper"/>
158 <origin xyz="0.02 -0.01 0" rpy="0 0 0"/>
159 <limit effort="1000.0" lower="0.0" upper="0.35" velocity="1.0"/>