<?xml version="1.0"?>
<robot name="arm">
<link name="base_link">
+ </link>
+
+ <link name="arm_base">
<visual>
<geometry>
- <mesh filename="package://arm_ros_conn/meshes/32985.stl" scale="1 1 1"/>
+ <mesh filename="package://arm_ros_conn/meshes/32985.stl"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
<geometry>
<box size="0.06 0.03 0.123"/>
</geometry>
- <origin xyz="0 0 0.0675"/>
+ <origin xyz="0 0 0.0615"/>
<material name="grey">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<link name="link5">
<visual>
<geometry>
- <mesh filename="package://arm_ros_conn/meshes/31019.stl" scale="1 1 1"/>
+ <mesh filename="package://arm_ros_conn/meshes/31019.stl"/>
</geometry>
<origin xyz="0.0 0 0" rpy="1.57075 0 0"/>
<material name="red">
</visual>
</link>
- <joint name="base_to_link1" type="continuous">
+ <joint name="base_link_to_arm_base" type="fixed">
<parent link="base_link"/>
+ <child link="arm_base"/>
+ <origin xyz="0 0 0.00375"/>
+ </joint>
+
+ <joint name="arm_base_to_link1" type="continuous">
+ <parent link="arm_base"/>
<child link="link1"/>
<axis xyz="0 0 1"/>
<origin xyz="0 0.099 0"/>
<parent link="link1"/>
<child link="link2"/>
<axis xyz="0 0 1"/>
- <origin xyz="0.0 0.0 0.135" rpy="1.57075 0 0"/>
+ <origin xyz="0.0 0.0 0.123" rpy="1.57075 0 0"/>
<limit effort="1000.0" lower="0.15045941827537324" upper="3.6110260386089577" velocity="1.0"/>
</joint>