+<?xml version="1.0"?>
+
+<!--
+For IKFast:
+- All rotation about Z-Axis
+- Gripper base at offset from last link
+- Gripper base points to Z-Direction
+-->
+
+<robot name="arm" xmlns:xacro="http://ros.org/wiki/xacro">
+ <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
+
+ <link name="base_link">
+ </link>
+
+ <link name="plate">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/32985.stl"/>
+ </geometry>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="arm_base">
+ </link>
+
+ <link name="link1">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/link1.stl"/>
+ </geometry>
+ <origin xyz="0 0 0.0615"/>
+ <material name="grey">
+ <color rgba="0.5 0.5 0.5 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="link2">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/link2.stl"/>
+ </geometry>
+ <origin xyz="0.120 0 0" rpy="1.5708 0 1.5708"/>
+ <material name="grey">
+ <color rgba="0.5 0.5 0.5 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="link3">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/link3.stl"/>
+ </geometry>
+ <origin xyz="0 0.0675 0" rpy="1.5708 0 0"/>
+ <material name="grey">
+ <color rgba="0.5 0.5 0.5 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="link4">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/link4.stl"/>
+ </geometry>
+ <origin xyz="0 0 0.015" rpy="0 0 0"/>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="link5">
+ <visual>
+ <geometry>
+ <mesh filename="package://arm_ros_conn/meshes/31019.stl"/>
+ </geometry>
+ <origin xyz="0.0 0 0" rpy="0 0 0"/>
+ <material name="red">
+ <color rgba="1 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="gripper_pole">
+ </link>
+
+ <link name="gripper_center">
+ </link>
+
+ <link name="left_gripper">
+ <visual>
+ <origin xyz="0.025 0 0" rpy="-1.5708 3.1416 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>
+
+ <link name="right_gripper">
+ <visual>
+ <origin xyz="0.025 0 0" rpy="-1.5708 3.1416 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>
+
+ <link name="link2_motor_extension">
+ <visual>
+ <geometry>
+ <box size="0.015 0.015 0.10"/>
+ </geometry>
+ <origin xyz="0 0 0.05" rpy="0 0 0"/>
+ <material name="grey">
+ <color rgba="0.5 0.5 0.5 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <link name="plate_box">
+ <visual>
+ <geometry>
+ <box size="0.08 0.185 0.035"/>
+ </geometry>
+ <origin xyz="0 0 0.0175" rpy="0 0 0"/>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
+
+ <joint name="plate_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="plate"/>
+ <origin xyz="0 0 0.00375"/>
+ </joint>
+
+ <joint name="arm_base_joint" type="fixed">
+ <parent link="plate"/>
+ <child link="arm_base"/>
+ <origin xyz="0 0.099 0"/>
+ </joint>
+
+ <joint name="link1_joint" type="revolute">
+ <parent link="arm_base"/>
+ <child link="link1"/>
+ <axis xyz="0 0 -1"/>
+ <limit effort="1.0" lower="0.0" upper="5.672320068981571" velocity="0.2"/>
+ </joint>
+
+ <joint name="link2_joint" type="revolute">
+ <parent link="link1"/>
+ <child link="link2"/>
+ <axis xyz="0 0 1"/>
+ <origin xyz="0.0 0.0 0.123" rpy="1.5708 0 0"/>
+ <limit effort="1.0" lower="0.1505" upper="3.611" velocity="0.1"/>
+ </joint>
+
+ <joint name="link3_joint" type="revolute">
+ <parent link="link2"/>
+ <child link="link3"/>
+ <axis xyz="0 0 -1"/>
+ <origin xyz="0.240 0 0" rpy="0 0 0"/>
+ <limit effort="1.0" lower="0" upper="3.1416" velocity="0.2"/>
+ </joint>
+
+ <joint name="link4_joint" type="revolute">
+ <parent link="link3"/>
+ <child link="link4"/>
+ <axis xyz="0 0 -1"/>
+ <origin xyz="0 0.135 0" rpy="-1.5708 0 0"/>
+ <limit effort="1.0" lower="-0.15708" upper="5.4978" velocity="0.5"/>
+ </joint>
+
+ <joint name="link5_joint" type="revolute">
+ <parent link="link4"/>
+ <child link="link5"/>
+ <axis xyz="0 0 1"/>
+ <origin xyz="0 0 0.06" rpy="1.5708 0 0"/>
+ <limit effort="1.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"/>
+ <origin xyz="0 0.02275 0" rpy="1.5708 0 1.5708"/>
+ </joint>
+
+ <joint name="gripper_center_joint" type="fixed">
+ <parent link="gripper_pole"/>
+ <child link="gripper_center"/>
+ <origin xyz="0.08 0 0" rpy="0 0 0"/>
+ </joint>
+
+ <joint name="left_gripper_joint" type="revolute">
+ <parent link="gripper_pole"/>
+ <child link="left_gripper"/>
+ <axis xyz="0 0 1"/>
+ <origin xyz="0 0.015 0" rpy="0 0 0"/>
+ <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
+ </joint>
+
+ <joint name="right_gripper_joint" type="revolute">
+ <parent link="gripper_pole"/>
+ <child link="right_gripper"/>
+ <axis xyz="0 0 1"/>
+ <origin xyz="0 -0.015 0" rpy="3.1416 0 0"/>
+ <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
+ </joint>
+
+ <joint name="link2_motor_extension_joint" type="fixed">
+ <parent link="link2"/>
+ <child link="link2_motor_extension"/>
+ <origin xyz="0.165 -0.03 0" rpy="1.5708 0 0"/>
+ </joint>
+
+ <joint name="plate_box_joint" type="fixed">
+ <parent link="plate"/>
+ <child link="plate_box"/>
+ <origin xyz="-0.04 -0.035 0" rpy="0 0 0"/>
+ </joint>
+
+ <xacro:asus_camera name="camera" parent="link2">
+ <origin xyz="0.18 -0.03 -0.05" rpy="0 3.1416 -1.5708"/>
+ </xacro:asus_camera>
+</robot>