Last active
February 17, 2021 14:44
-
-
Save aliadnani/b7b92c9a545b181cf9c629f68ab5c4ce to your computer and use it in GitHub Desktop.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0" ?> | |
<!-- =================================================================================== --> | |
<!-- | This document was autogenerated by xacro from sisbot.xacro | --> | |
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> | |
<!-- =================================================================================== --> | |
<robot name="ur3_robotiq_140" xmlns:xacro="http://ros.org/wiki/xacro"> | |
<!--################################################ | |
######## arm ####### | |
####################################################--> | |
<link name="base_link"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/base.dae"/> | |
</geometry> | |
<material name="LightGrey"> | |
<color rgba="0.7 0.7 0.7 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/base.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="2.0"/> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> | |
<inertia ixx="0.0030531654454" ixy="0.0" ixz="0.0" iyy="0.0030531654454" iyz="0.0" izz="0.005625"/> | |
</inertial> | |
</link> | |
<joint name="shoulder_pan_joint" type="revolute"> | |
<parent link="base_link"/> | |
<child link="shoulder_link"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1519"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.16"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="shoulder_link"> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/shoulder.dae"/> | |
</geometry> | |
<material name="DarkGray"> | |
<color rgba="0.5 0.5 0.5 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/shoulder.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="2.0"/> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> | |
<inertia ixx="0.008093163429399999" ixy="0.0" ixz="0.0" iyy="0.008093163429399999" iyz="0.0" izz="0.005625"/> | |
</inertial> | |
</link> | |
<joint name="shoulder_lift_joint" type="revolute"> | |
<parent link="shoulder_link"/> | |
<child link="upper_arm_link"/> | |
<origin rpy="0.0 1.5707963267948966 0.0" xyz="0.0 0.1198 0.0"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.16"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="upper_arm_link"> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/upperarm.dae"/> | |
</geometry> | |
<material name="LightGrey"> | |
<color rgba="0.7 0.7 0.7 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/upperarm.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="3.42"/> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.121825"/> | |
<inertia ixx="0.021728483221103233" ixy="0.0" ixz="0.0" iyy="0.021728483221103233" iyz="0.0" izz="0.00961875"/> | |
</inertial> | |
</link> | |
<joint name="elbow_joint" type="revolute"> | |
<parent link="upper_arm_link"/> | |
<child link="forearm_link"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.0925 0.24365"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="150.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="3.15"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="forearm_link"> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/forearm.dae"/> | |
</geometry> | |
<material name="LightGrey"> | |
<color rgba="0.7 0.7 0.7 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/forearm.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="1.26"/> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.106625"/> | |
<inertia ixx="0.006546806443776375" ixy="0.0" ixz="0.0" iyy="0.006546806443776375" iyz="0.0" izz="0.00354375"/> | |
</inertial> | |
</link> | |
<joint name="wrist_1_joint" type="revolute"> | |
<parent link="forearm_link"/> | |
<child link="wrist_1_link"/> | |
<origin rpy="0.0 1.5707963267948966 0.0" xyz="0.0 0.0 0.21325"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="54.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.2"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="wrist_1_link"> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/wrist1.dae"/> | |
</geometry> | |
<material name="DarkGray"> | |
<color rgba="0.5 0.5 0.5 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/wrist1.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.8"/> | |
<origin rpy="0 0 0" xyz="0.0 0.08505 0.0"/> | |
<inertia ixx="0.002084999166" ixy="0.0" ixz="0.0" iyy="0.002084999166" iyz="0.0" izz="0.00225"/> | |
</inertial> | |
</link> | |
<joint name="wrist_2_joint" type="revolute"> | |
<parent link="wrist_1_link"/> | |
<child link="wrist_2_link"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.08505 0.0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="54.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.2"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="wrist_2_link"> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/wrist2.dae"/> | |
</geometry> | |
<material name="DarkGray"> | |
<color rgba="0.5 0.5 0.5 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/wrist2.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.8"/> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.08535"/> | |
<inertia ixx="0.002084999166" ixy="0.0" ixz="0.0" iyy="0.002084999166" iyz="0.0" izz="0.00225"/> | |
</inertial> | |
</link> | |
<joint name="wrist_3_joint" type="revolute"> | |
<parent link="wrist_2_link"/> | |
<child link="wrist_3_link"/> | |
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.08535"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="54.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.2"/> | |
<dynamics damping="0.0" friction="0.0"/> | |
</joint> | |
<link name="wrist_3_link"> | |
<visual> | |
<geometry> | |
<mesh filename="../meshes/ur3/visual/wrist3.dae"/> | |
</geometry> | |
<material name="LightGrey"> | |
<color rgba="0.7 0.7 0.7 1.0"/> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh filename="../meshes/ur3/collision/wrist3.stl"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.35"/> | |
<origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0619 0.0"/> | |
<inertia ixx="0.00013626661215999998" ixy="0.0" ixz="0.0" iyy="0.00013626661215999998" iyz="0.0" izz="0.0001792"/> | |
</inertial> | |
</link> | |
<joint name="ee_fixed_joint" type="fixed"> | |
<parent link="wrist_3_link"/> | |
<child link="ee_link"/> | |
<origin rpy="0.0 0.0 1.5707963267948966" xyz="0.0 0.0819 0.0"/> | |
</joint> | |
<link name="ee_link"> | |
<collision> | |
<geometry> | |
<box size="0.01 0.01 0.01"/> | |
</geometry> | |
<origin rpy="0 0 0" xyz="-0.01 0 0"/> | |
</collision> | |
</link> | |
<!--################################################ | |
######## gripper ##### | |
####################################################--> | |
<link name="robotiq_140_robotiq_arg2f_base_link"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00013 0.00011 0.03284"/> | |
<mass value="0.52954"/> | |
<inertia ixx="573495E-9" ixy="-554E-9" ixz="2628E-9" iyy="681780E-9" iyz="607E-9" izz="483281E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/GRIPPER_base_axis.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name="Gazebo/Black"> | |
<color rgba="0.1 0.1 0.1 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/GRIPPER_base_axis.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_robotiq_arg2f_base_link"> | |
<material>Gazebo/Black</material> | |
<selfCollide>True</selfCollide> | |
</gazebo> | |
<!-- robotiq_85_left_knuckle_link --> | |
<link name="robotiq_140_left_outer_knuckle"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.01616 0 -0.00133"/> | |
<mass value="0.0131"/> | |
<inertia ixx="325.5E-9" ixy="0" ixz="197.94E-9" iyy="2306.36E-9" iyz="0" izz="2176E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_outer_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name=""> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_outer_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_left_outer_knuckle"> | |
<material>Gazebo/Grey</material> | |
<selfCollide>True</selfCollide> | |
</gazebo> | |
<!-- robotiq_85_right_knuckle_link --> | |
<link name="robotiq_140_right_outer_knuckle"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.01616 0 -0.00133"/> | |
<mass value="0.0131"/> | |
<inertia ixx="325.5E-9" ixy="0" ixz="-197.94E-9" iyy="2306.36E-9" iyz="0" izz="2176E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_outer_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name=""> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_outer_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_right_outer_knuckle"> | |
<material>Gazebo/Grey</material> | |
<selfCollide>True</selfCollide> | |
</gazebo> | |
<!-- robotiq_85_left_inner_knuckle_link --> | |
<link name="robotiq_140_left_inner_knuckle"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.03332 0 0.0379"/> | |
<mass value="0.04476"/> | |
<inertia ixx="28054E-9" ixy="0" ixz="-19174E-9" iyy="39758E-9" iyz="0" izz="23453E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_inner_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name=""> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_inner_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_left_inner_knuckle"> | |
<material>Gazebo/Black</material> | |
<selfCollide>False</selfCollide> | |
</gazebo> | |
<!-- robotiq_85_right_inner_knuckle_link --> | |
<link name="robotiq_140_right_inner_knuckle"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.03332 0 0.0379"/> | |
<mass value="0.04476"/> | |
<inertia ixx="28054E-9" ixy="0" ixz="19174E-9" iyy="39758E-9" iyz="0" izz="23453E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_inner_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name="Gazebo/Black"> | |
<color rgba="0.1 0.1 0.1 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_inner_knuckle.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_right_inner_knuckle"> | |
<material>Gazebo/Black</material> | |
<selfCollide>False</selfCollide> | |
</gazebo> | |
<!-- robotiq_85_left_finger_link --> | |
<link name="robotiq_140_left_inner_finger"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.01563 0 0.02522"/> | |
<mass value="0.045"/> | |
<inertia ixx="26663E-9" ixy="0" ixz="5579E-9" iyy="28009E-9" iyz="0" izz="4368E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_inner_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name=""> | |
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_inner_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_left_inner_finger"> | |
<material>Gazebo/Black</material> | |
<selfCollide>False</selfCollide> | |
</gazebo> | |
<!-- robotiq_85_right_finger_link --> | |
<link name="robotiq_140_right_inner_finger"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.01563 0 0.02522"/> | |
<mass value="0.045"/> | |
<inertia ixx="26663E-9" ixy="0" ixz="-5579E-9" iyy="28009E-9" iyz="0" izz="4368E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_inner_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name="Gazebo/Black"> | |
<color rgba="0.1 0.1 0.1 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_inner_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_right_inner_finger"> | |
<material>Gazebo/Black</material> | |
<selfCollide>False</selfCollide> | |
</gazebo> | |
<!-- robot --> | |
<link name="robotiq_140_left_outer_finger"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.01482 0 0.03451"/> | |
<mass value="0.07637"/> | |
<inertia ixx="45513E-9" ixy="0" ixz="-20691E-9" iyy="52570E-9" iyz="0" izz="17804E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_outer_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name="Gazebo/Black"> | |
<color rgba="0.1 0.1 0.1 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_left_outer_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_left_outer_finger"> | |
<material>Gazebo/Black</material> | |
<selfCollide>True</selfCollide> | |
</gazebo> | |
<!-- robot --> | |
<link name="robotiq_140_right_outer_finger"> | |
<contact> | |
<lateral_friction value="1"/> | |
</contact> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.01482 0 0.03451"/> | |
<mass value="0.07637"/> | |
<inertia ixx="45513E-9" ixy="0" ixz="20691E-9" iyy="52570E-9" iyz="0" izz="17804E-9"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_outer_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
<material name="Gazebo/Black"> | |
<color rgba="0.1 0.1 0.1 1"/> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://robotiq_140_gripper_description/meshes/robotiq_140_right_outer_finger.dae" scale="0.001 0.001 0.001"/> | |
</geometry> | |
</collision> | |
</link> | |
<gazebo reference="robotiq_140_right_outer_finger"> | |
<material>Gazebo/Black</material> | |
<selfCollide>True</selfCollide> | |
</gazebo> | |
<!-- robot --> | |
<joint name="robotiq_arg2f_base_to_robotiq_140_left_outer_knuckle" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0306 0 0.05466"/> | |
<parent link="robotiq_140_robotiq_arg2f_base_link"/> | |
<child link="robotiq_140_left_outer_knuckle"/> | |
<axis xyz="0 -1 0"/> | |
<limit effort="18.65" lower="0" upper="0.78574722925" velocity="2.0"/> | |
<mimic joint="robotiq_140_joint_finger" multiplier="1" offset="0"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_140_joint_finger" type="revolute"> | |
<origin rpy="0 0 0" xyz="-0.0306 0 0.05466"/> | |
<parent link="robotiq_140_robotiq_arg2f_base_link"/> | |
<child link="robotiq_140_right_outer_knuckle"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="18.65" lower="0" upper="0.78574722925" velocity="3.54"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_arg2f_base_to_robotiq_140_left_inner_knuckle" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0127 0 0.06118"/> | |
<parent link="robotiq_140_robotiq_arg2f_base_link"/> | |
<child link="robotiq_140_left_inner_knuckle"/> | |
<axis xyz="0 -1 0"/> | |
<limit effort="18.65" lower="0" upper="0.78574722925" velocity="3.54"/> | |
<mimic joint="robotiq_140_joint_finger" multiplier="1" offset="0"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_arg2f_base_to_robotiq_140_right_inner_knuckle" type="revolute"> | |
<origin rpy="0 0 0" xyz="-0.0127 0 0.06118"/> | |
<parent link="robotiq_140_robotiq_arg2f_base_link"/> | |
<child link="robotiq_140_right_inner_knuckle"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="18.65" lower="0" upper="0.78574722925" velocity="3.54"/> | |
<mimic joint="robotiq_140_joint_finger" multiplier="1" offset="0"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_140_left_outer_knuckle_to_finger" type="fixed"> | |
<origin rpy="0 0 0" xyz="0.03142 0 -0.00453"/> | |
<parent link="robotiq_140_left_outer_knuckle"/> | |
<child link="robotiq_140_left_outer_finger"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_140_right_outer_knuckle_to_finger" type="fixed"> | |
<origin rpy="0 0 0" xyz="-0.03142 0 -0.00453"/> | |
<parent link="robotiq_140_right_outer_knuckle"/> | |
<child link="robotiq_140_right_outer_finger"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_140_left_outer_finger_to_inner" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.03543 0 0.0789"/> | |
<parent link="robotiq_140_left_outer_finger"/> | |
<child link="robotiq_140_left_inner_finger"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="18.65" lower="0" upper="0.78574722925" velocity="3.54"/> | |
<mimic joint="robotiq_140_joint_finger" multiplier="1" offset="0"/> | |
</joint> | |
<!-- robot --> | |
<joint name="robotiq_140_right_outer_finger_to_inner" type="revolute"> | |
<origin rpy="0 0 0" xyz="-0.03543 0 0.0789"/> | |
<parent link="robotiq_140_right_outer_finger"/> | |
<child link="robotiq_140_right_inner_finger"/> | |
<axis xyz="0 -1 0"/> | |
<limit effort="18.65" lower="0" upper="0.78574722925" velocity="3.54"/> | |
<mimic joint="robotiq_140_joint_finger" multiplier="1" offset="0"/> | |
</joint> | |
<!--################################################ | |
######## connect model ##### | |
####################################################--> | |
<link name="world"/> | |
<!-- connect gripper to arm --> | |
<joint name="arm_gripper_joint" type="fixed"> | |
<parent link="ee_link"/> | |
<child link="robotiq_140_robotiq_arg2f_base_link"/> | |
<origin rpy="-1.57 1.57 -1.57" xyz="0.0 0.0 0.0"/> | |
</joint> | |
<!-- connect arm to world --> | |
<joint name="world_arm_joint" type="fixed"> | |
<parent link="world"/> | |
<child link="base_link"/> | |
<origin rpy="0.0 0.0 0" xyz="0 0 0.0"/> | |
</joint> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment