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"/>
20 <box size="0.06 0.03 0.123"/>
22 <origin xyz="0 0 0.0615"/>
23 <material name="grey">
24 <color rgba="0.5 0.5 0.5 1"/>
32 <box size="0.240 0.06 0.03"/>
34 <origin xyz="0.120 0 0.0" rpy="0 0 0"/>
35 <material name="grey">
36 <color rgba="0.5 0.5 0.5 1"/>
44 <box size="0.06 0.135 0.03"/>
46 <origin xyz="0.0 0.0675 0.0" rpy="0 0 0"/>
47 <material name="grey">
48 <color rgba="0.5 0.5 0.5 1"/>
56 <cylinder radius="0.045" length="0.03"/>
58 <origin xyz="0.015 0 0" rpy="0 1.57075 0"/>
59 <material name="black">
60 <color rgba="0 0 0 1"/>
68 <mesh filename="package://arm_ros_conn/meshes/31019.stl"/>
70 <origin xyz="0.0 0 0" rpy="1.57075 0 0"/>
72 <color rgba="1 0 0 1"/>
77 <link name="gripper_pole">
80 <link name="left_gripper">
82 <origin xyz="0.025 0 0" rpy="-1.57075 3.1415 0"/>
84 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
87 <color rgba="1 0 0 1"/>
92 <link name="right_gripper">
94 <origin xyz="0.025 0 0" rpy="1.57075 3.1415 0"/>
96 <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
99 <color rgba="1 0 0 1"/>
104 <joint name="base_link_to_arm_base" type="fixed">
105 <parent link="base_link"/>
106 <child link="arm_base"/>
107 <origin xyz="0 0 0.00375"/>
110 <joint name="arm_base_to_link1" type="continuous">
111 <parent link="arm_base"/>
112 <child link="link1"/>
114 <origin xyz="0 0.099 0"/>
115 <limit effort="1000.0" lower="-5.672320068981571" upper="0.0" velocity="1.0"/>
118 <joint name="link_1_2_joint" type="continuous">
119 <parent link="link1"/>
120 <child link="link2"/>
122 <origin xyz="0.0 0.0 0.123" rpy="1.57075 0 0"/>
123 <limit effort="1000.0" lower="0.15045941827537324" upper="3.6110260386089577" velocity="1.0"/>
126 <joint name="link_2_3_joint" type="continuous">
127 <parent link="link2"/>
128 <child link="link3"/>
130 <origin xyz="0.240 0.0 0.0" rpy="0 0 0"/>
131 <limit effort="1000.0" lower="-3.141592653589793" upper="0.0" velocity="1.0"/>
134 <joint name="link_3_4_joint" type="continuous">
135 <parent link="link3"/>
136 <child link="link4"/>
138 <origin xyz="0 0.135 0.0" rpy="1.57075 0 1.57075"/>
139 <limit effort="1000.0" lower="-7.679448708775051" upper="0.6981317007977319" velocity="1.0"/>
142 <joint name="link_4_5_joint" type="continuous">
143 <parent link="link4"/>
144 <child link="link5"/>
146 <origin xyz="0.06 0.0 0.0" rpy="0 0 0"/>
147 <limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
150 <joint name="gripper_pole_joint" type="fixed">
151 <parent link="link5"/>
152 <child link="gripper_pole"/>
155 <joint name="left_gripper_joint" type="revolute">
156 <parent link="gripper_pole"/>
157 <child link="left_gripper"/>
159 <origin xyz="0.02 0.01 0" rpy="0 0 0" />
160 <limit effort="1000.0" lower="0.0" upper="0.35" velocity="1.0"/>
163 <joint name="right_gripper_joint" type="revolute">
164 <parent link="gripper_pole"/>
165 <child link="right_gripper"/>
167 <origin xyz="0.02 -0.01 0" rpy="0 0 0"/>
168 <limit effort="1000.0" lower="0.0" upper="0.35" velocity="1.0"/>