--- /dev/null
+<?xml version="1.0" encoding="utf-8"?>
+<!-- =================================================================================== -->
+<!-- | This document was autogenerated by xacro from open_manipulator.urdf.xacro | -->
+<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
+<!-- =================================================================================== -->
+<!-- Open_Manipulator Chain -->
+<robot name="open_manipulator" xmlns:xacro="http://ros.org/wiki/xacro">
+ <!-- World -->
+ <gazebo reference="world">
+ </gazebo>
+ <gazebo reference="link1">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <gazebo reference="link2">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <gazebo reference="link3">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <gazebo reference="link4">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <gazebo reference="link5">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <gazebo reference="gripper_link">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <gazebo reference="gripper_link_sub">
+ <kp>1000000.0</kp>
+ <kd>100.0</kd>
+ <mu1>30.0</mu1>
+ <mu2>30.0</mu2>
+ <maxVel>1.0</maxVel>
+ <minDepth>0.001</minDepth>
+ <material>Gazebo/DarkGrey</material>
+ </gazebo>
+ <!-- end effector link -->
+ <gazebo reference="end_effector_link">
+ <material>Gazebo/Red</material>
+ </gazebo>
+ <!-- ros_control plugin -->
+ <gazebo>
+ <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
+ <robotNamespace>open_manipulator</robotNamespace>
+ <controlPeriod>0.001</controlPeriod>
+ <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
+ <legacyModeNS>true</legacyModeNS>
+ </plugin>
+ </gazebo>
+ <material name="black">
+ <color rgba="0.0 0.0 0.0 1.0"/>
+ </material>
+ <material name="white">
+ <color rgba="1.0 1.0 1.0 1.0"/>
+ </material>
+ <material name="red">
+ <color rgba="0.8 0.0 0.0 1.0"/>
+ </material>
+ <material name="blue">
+ <color rgba="0.0 0.0 0.8 1.0"/>
+ </material>
+ <material name="green">
+ <color rgba="0.0 0.8 0.0 1.0"/>
+ </material>
+ <material name="grey">
+ <color rgba="0.5 0.5 0.5 1.0"/>
+ </material>
+ <material name="orange">
+ <color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
+ </material>
+ <material name="brown">
+ <color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
+ </material>
+ <!-- Link 1 -->
+ <link name="link1">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <!-- <inertial>
+ <origin xyz="0 0 0" />
+ <mass value="0.082" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0"
+ iyy="0.1" iyz="0.0"
+ izz="0.1" />
+ </inertial>-->
+ <inertial>
+ <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04"/>
+ <mass value="7.9119962e-02"/>
+ <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07" iyy="2.1898364e-05" iyz="0.0" izz="1.9267361e-05"/>
+ </inertial>
+ </link>
+ <!-- Joint 1 -->
+ <joint name="joint1" type="revolute">
+ <parent link="link1"/>
+ <child link="link2"/>
+ <origin rpy="0 0 0" xyz="0.012 0.0 0.017"/>
+ <axis xyz="0 0 1"/>
+ <limit effort="1" lower="-3.14159265359" upper="3.14159265359" velocity="4.8"/>
+ </joint>
+ <transmission name="tran1">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="joint1">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="motor1">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ <!-- Link 2 -->
+ <link name="link2">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0.019"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0.019"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <!-- <inertial>
+ <origin xyz="0 0 0" />
+ <mass value="0.098" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0"
+ iyy="0.1" iyz="0.0"
+ izz="0.1" />
+ </inertial>-->
+ <inertial>
+ <origin xyz="-3.0184870e-04 5.4043684e-04 0.047433464"/>
+ <mass value="9.8406837e-02"/>
+ <inertia ixx="3.4543422e-05" ixy="-1.6031095e-08" ixz="-3.8375155e-07" iyy="3.2689329e-05" iyz="2.8511935e-08" izz="1.8850320e-05"/>
+ </inertial>
+ </link>
+ <!-- Joint 2 -->
+ <joint name="joint2" type="revolute">
+ <parent link="link2"/>
+ <child link="link3"/>
+ <origin rpy="0 0 0" xyz="0.0 0.0 0.0595"/>
+ <axis xyz="0 1 0"/>
+ <limit effort="1" lower="-2.0106192983" upper="2.0106192983" velocity="4.8"/>
+ </joint>
+ <transmission name="tran2">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="joint2">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="motor2">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ <!-- Link 3 -->
+ <link name="link3">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <!-- <inertial>
+ <origin xyz="0 0 0" />
+ <mass value="0.136" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0"
+ iyy="0.1" iyz="0.0"
+ izz="0.1" />
+ </inertial>-->
+ <inertial>
+ <origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01"/>
+ <mass value="1.3850917e-01"/>
+ <inertia ixx="3.3055381e-04" ixy="-9.7940978e-08" ixz="-3.8505711e-05" iyy="3.4290447e-04" iyz="-1.5717516e-06" izz="6.0346498e-05"/>
+ </inertial>
+ </link>
+ <!-- Joint 3 -->
+ <joint name="joint3" type="revolute">
+ <parent link="link3"/>
+ <child link="link4"/>
+ <origin rpy="0 0 0" xyz="0.024 0 0.128"/>
+ <axis xyz="0 1 0"/>
+ <limit effort="1" lower="-2.0106192983" upper="1.50796447372" velocity="4.8"/>
+ </joint>
+ <transmission name="tran3">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="joint3">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="motor3">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ <!-- Link 4 -->
+ <link name="link4">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <!-- <inertial>
+ <origin xyz="0 0 0" />
+ <mass value="0.131" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0"
+ iyy="0.1" iyz="0.0"
+ izz="0.1" />
+ </inertial>-->
+ <inertial>
+ <origin xyz="9.0909590e-02 3.8929816e-04 2.2413279e-04"/>
+ <mass value="1.3274562e-01"/>
+ <inertia ixx="3.0654178e-05" ixy="-1.2764155e-06" ixz="-2.6874417e-07" iyy="2.4230292e-04" iyz="1.1559550e-08" izz="2.5155057e-04"/>
+ </inertial>
+ </link>
+ <!-- Joint 4 -->
+ <joint name="joint4" type="revolute">
+ <parent link="link4"/>
+ <child link="link5"/>
+ <origin rpy="0 0 0" xyz="0.124 0.0 0.0"/>
+ <axis xyz="0 1 0"/>
+ <limit effort="1" lower="-1.79070781255" upper="2.04203522483" velocity="4.8"/>
+ </joint>
+ <transmission name="tran4">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="joint4">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="motor4">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ <!-- Link 5 -->
+ <link name="link5">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <!-- <inertial>
+ <origin xyz="0 0 0" />
+ <mass value="0.141" />
+ <inertia ixx="0.1" ixy="0.0" ixz="0.0"
+ iyy="0.1" iyz="0.0"
+ izz="0.1" />
+ </inertial>-->
+ <inertial>
+ <origin xyz="4.4206755e-02 3.6839985e-07 8.9142216e-03"/>
+ <mass value="1.4327573e-01"/>
+ <inertia ixx="8.0870749e-05" ixy="0.0" ixz="-1.0157896e-06" iyy="7.5980465e-05" iyz="0.0" izz="9.3127351e-05"/>
+ </inertial>
+ </link>
+ <!-- Gripper link -->
+ <link name="gripper_link">
+ <visual>
+ <origin rpy="0 0 0" xyz="0.0 0.0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0.0 0.0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin xyz="0 0 0"/>
+ <mass value="0.017"/>
+ <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0" iyy="1.0e-03" iyz="0.0" izz="1.0e-03"/>
+ </inertial>
+ <!-- <inertial>
+ <origin xyz="${0.028 + 8.3720668e-03} ${0.0246 + 9.9696160e-03} -4.2836895e-07" />
+ <mass value="3.2218127e-02" />
+ <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
+ iyy="2.2552871e-05" iyz="-3.1463634e-10"
+ izz="1.7605306e-05" />
+ </inertial>-->
+ </link>
+ <!-- Gripper joint -->
+ <joint name="gripper" type="prismatic">
+ <parent link="link5"/>
+ <child link="gripper_link"/>
+ <origin rpy="0 0 0" xyz="0.0817 0.021 0.0"/>
+ <axis xyz="0 1 0"/>
+ <limit effort="1" lower="-0.010" upper="0.019" velocity="4.8"/>
+ </joint>
+ <transmission name="tran5">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="gripper">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="motor5">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ <!-- Gripper link sub -->
+ <link name="gripper_link_sub">
+ <visual>
+ <origin rpy="0 0 0" xyz="0.0 -0.0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <material name="grey"/>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0.0 -0.0 0"/>
+ <geometry>
+ <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin xyz="0 0 0"/>
+ <mass value="0.017"/>
+ <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0" iyy="1.0e-03" iyz="0.0" izz="1.0e-03"/>
+ </inertial>
+ <!-- <inertial>
+ <origin xyz="${0.028 + 8.3720668e-03} ${-0.0246 - 9.9696160e-03} -4.2836895e-07" />
+ <mass value="3.2218127e-02" />
+ <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
+ iyy="2.2552871e-05" iyz="-3.1463634e-10"
+ izz="1.7605306e-05" />
+ </inertial>-->
+ </link>
+ <!-- Gripper joint sub -->
+ <joint name="gripper_sub" type="prismatic">
+ <parent link="link5"/>
+ <child link="gripper_link_sub"/>
+ <origin rpy="0 0 0" xyz="0.0817 -0.021 0"/>
+ <axis xyz="0 -1 0"/>
+ <limit effort="1" lower="-0.010" upper="0.019" velocity="4.8"/>
+ <mimic joint="gripper" multiplier="1"/>
+ </joint>
+ <transmission name="tran6">
+ <type>transmission_interface/SimpleTransmission</type>
+ <joint name="gripper_sub">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="motor6">
+ <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+ <!-- end effector joint -->
+ <joint name="end_effector_joint" type="fixed">
+ <origin rpy="0 0 0" xyz="0.126 0.0 0.0"/>
+ <parent link="link5"/>
+ <child link="end_effector_link"/>
+ </joint>
+ <!-- end effector link -->
+ <link name="end_effector_link">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.01 0.01 0.01"/>
+ </geometry>
+ <material name="red"/>
+ </visual>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+ <mass value="0.001"/>
+ <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06"/>
+ </inertial>
+ </link>
+</robot>