<?xml version="1.0"?>
<robot name="arm">
<link name="base_link">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/32985.stl" scale="1 1 1"/>
+ </geometry>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
</link>
<link name="link1">
<visual>
<geometry>
- <box size="0.06 0.03 0.135"/>
+ <box size="0.06 0.03 0.123"/>
</geometry>
<origin xyz="0 0 0.0675"/>
<material name="grey">
</visual>
</link>
- <link name="gripper_pole1">
+ <link name="link4">
<visual>
<geometry>
<cylinder radius="0.045" length="0.03"/>
</visual>
</link>
- <link name="gripper_pole2">
+ <link name="link5">
<visual>
<geometry>
- <cylinder radius="0.03" length="0.015"/>
+ <mesh filename="package://arm_ros_conn/meshes/31019.stl" scale="1 1 1"/>
</geometry>
<origin xyz="0.0 0 0" rpy="1.57075 0 0"/>
<material name="red">
</visual>
</link>
+ <link name="gripper_pole">
+ </link>
+
<link name="left_gripper">
<visual>
<origin xyz="0.025 0 0" rpy="-1.57075 3.1415 0"/>
<geometry>
<mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
</geometry>
+ <material name="red">
+ <color rgba="1 0 0 1"/>
+ </material>
</visual>
</link>
<geometry>
<mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
</geometry>
+ <material name="red">
+ <color rgba="1 0 0 1"/>
+ </material>
</visual>
</link>
<parent link="base_link"/>
<child link="link1"/>
<axis xyz="0 0 1"/>
+ <origin xyz="0 0.099 0"/>
<limit effort="1000.0" lower="-5.672320068981571" upper="0.0" velocity="1.0"/>
</joint>
<limit effort="1000.0" lower="-3.141592653589793" upper="0.0" velocity="1.0"/>
</joint>
- <joint name="gripper_joint_1" type="continuous">
+ <joint name="link_3_4_joint" type="continuous">
<parent link="link3"/>
- <child link="gripper_pole1"/>
+ <child link="link4"/>
<axis xyz="1 0 0"/>
<origin xyz="0 0.135 0.0" rpy="1.57075 0 1.57075"/>
<limit effort="1000.0" lower="-7.679448708775051" upper="0.6981317007977319" velocity="1.0"/>
</joint>
- <joint name="gripper_joint_2" type="continuous">
- <parent link="gripper_pole1"/>
- <child link="gripper_pole2"/>
+ <joint name="link_4_5_joint" type="continuous">
+ <parent link="link4"/>
+ <child link="link5"/>
<axis xyz="0 1 0"/>
<origin xyz="0.06 0.0 0.0" rpy="0 0 0"/>
<limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
</joint>
+ <joint name="gripper_pole_joint" type="fixed">
+ <parent link="link5"/>
+ <child link="gripper_pole"/>
+ </joint>
+
<joint name="left_gripper_joint" type="revolute">
- <parent link="gripper_pole2"/>
+ <parent link="gripper_pole"/>
<child link="left_gripper"/>
<axis xyz="0 0 1"/>
<origin xyz="0.02 0.01 0" rpy="0 0 0" />
</joint>
<joint name="right_gripper_joint" type="revolute">
- <parent link="gripper_pole2"/>
+ <parent link="gripper_pole"/>
<child link="right_gripper"/>
<axis xyz="0 0 -1"/>
<origin xyz="0.02 -0.01 0" rpy="0 0 0"/>