|
<?xml version="1.0" ?> |
|
<robot name="panda" xmlns:xacro="http://www.ros.org/wiki/xacro"> |
|
<link name="panda_link0"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link0.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link0.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<link name="panda_link1"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link1.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link1.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint1" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/> |
|
<origin rpy="0 0 0" xyz="0 0 0.333"/> |
|
<parent link="panda_link0"/> |
|
<child link="panda_link1"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_link2"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link2.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link2.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint2" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/> |
|
<origin rpy="-1.57079632679 0 0" xyz="0 0 0"/> |
|
<parent link="panda_link1"/> |
|
<child link="panda_link2"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="87" lower="-1.7628" upper="1.7628" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_link3"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link3.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link3.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint3" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/> |
|
<origin rpy="1.57079632679 0 0" xyz="0 -0.316 0"/> |
|
<parent link="panda_link2"/> |
|
<child link="panda_link3"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/> |
|
</joint> |
|
<link name="panda_link4"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link4.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link4.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint4" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/> |
|
<origin rpy="1.57079632679 0 0" xyz="0.0825 0 0"/> |
|
<parent link="panda_link3"/> |
|
<child link="panda_link4"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750"/> |
|
|
|
|
|
|
|
</joint> |
|
<link name="panda_link5"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link5.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link5.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint5" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/> |
|
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/> |
|
<parent link="panda_link4"/> |
|
<child link="panda_link5"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/> |
|
</joint> |
|
<link name="panda_link6"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link6.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link6.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint6" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/> |
|
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/> |
|
<parent link="panda_link5"/> |
|
<child link="panda_link6"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.6100"/> |
|
|
|
|
|
</joint> |
|
<link name="panda_link7"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/visual/link7.dae"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="package://franka_meshes/collision/link7.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="panda_joint7" type="revolute"> |
|
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/> |
|
<origin rpy="1.57079632679 0 0" xyz="0.088 0 0"/> |
|
<parent link="panda_link6"/> |
|
<child link="panda_link7"/> |
|
<axis xyz="0 0 1"/> |
|
<dynamics damping="10.0"/> |
|
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/> |
|
</joint> |
|
<joint name="panda_hand_joint" type="fixed"> |
|
<parent link="panda_link7"/> |
|
<child link="forearm"/> |
|
<origin rpy="0 0 0.78539816" xyz="0 0 0.107"/> |
|
</joint> |
|
<link name="forearm"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.09" /> |
|
<mass value="3.0" /> |
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<geometry name="shadow_forearm_geom"> |
|
<mesh filename="meshes/forearm.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 0.0" /> |
|
<geometry name="shadow_forearm_collision"> |
|
<mesh filename="meshes/forearm.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
|
|
<joint name="WRJ2" type="revolute"> |
|
<parent link="forearm" /> |
|
<child link="wrist" /> |
|
|
|
<origin rpy="0 0 0" xyz="0 -0.010 0.213" /> |
|
<axis xyz="0 1 0" /> |
|
|
|
<limit effort="10" lower="-0.489" upper="0.14" velocity="1.0" /> |
|
<dynamics damping="100.5" /> |
|
</joint> |
|
|
|
<link name="wrist"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0.0 0.0" /> |
|
|
|
<mass value="0.1" /> |
|
<inertia ixx="0.120" ixy="0.0" ixz="0.0" iyy="0.148" iyz="0.0" izz="0.0438" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<geometry name="wrist_visual"> |
|
<mesh filename="package://meshes/wrist.obj"/> |
|
</geometry> |
|
<material name="LightGrey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<geometry name="wrist_collision_geom"> |
|
<mesh filename="package://meshes/wrist.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
|
|
<link name="palm"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.035" /> |
|
<mass value="0.3" /> |
|
<inertia ixx="0.5" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="0.3" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="palm_visual"> |
|
<mesh filename="package://meshes/palm_left.stl" scale="0.001 0.001 0.001"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0.00 0 0.0" /> |
|
<geometry name="palm_collision_geom"> |
|
<mesh filename="package://meshes/palm_left.stl" scale="0.001 0.001 0.001"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
|
|
<joint name="WRJ1" type="revolute"> |
|
<parent link="wrist" /> |
|
<child link="palm" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.034" /> |
|
<axis xyz="1 0 0" /> |
|
|
|
<limit effort="5" lower="-0.698" upper="0.489" velocity="1.0" /> |
|
<dynamics damping="100.5" /> |
|
</joint> |
|
|
|
<link name="ffknuckle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
|
|
<mass value="0.008" /> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.000" /> |
|
<geometry name="knuckle_visual"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
<material name="LightGrey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="knuckle_collision_geom"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="FFJ4" type="revolute"> |
|
<parent link="palm" /> |
|
<child link="ffknuckle" /> |
|
|
|
<origin rpy="0 0 0" xyz="0.033 0 0.095" /> |
|
<axis xyz="0 1 0" /> |
|
<limit effort="100" lower="-0.349" upper="0.349" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="ffproximal"> |
|
<inertial> |
|
<mass value="0.014" /> |
|
<origin xyz="0 0 0.0225" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="proximal_visual"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="proximal_collision_geom"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="FFJ3" type="revolute"> |
|
<parent link="ffknuckle" /> |
|
<child link="ffproximal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="ffmiddle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.0125" /> |
|
<mass value="0.012" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="middle_visual"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="middle_collision_geom"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="FFJ2" type="revolute"> |
|
<parent link="ffproximal" /> |
|
<child link="ffmiddle" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.045" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="ffdistal"> |
|
<inertial> |
|
<mass value="0.010" /> |
|
<origin xyz="0 0 0.013" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_visual"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
|
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_collision_geom"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="FFJ1" type="revolute"> |
|
<parent link="ffmiddle" /> |
|
<child link="ffdistal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.025" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="mfknuckle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
|
|
<mass value="0.008" /> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0005" /> |
|
<geometry name="knuckle_visual"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
<material name="LightGrey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0005" /> |
|
<geometry name="knuckle_collision_geom"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="MFJ4" type="revolute"> |
|
<parent link="palm" /> |
|
<child link="mfknuckle" /> |
|
|
|
<origin rpy="0 0 0" xyz="0.011 0 0.099" /> |
|
<axis xyz="0 1 0" /> |
|
<limit effort="100" lower="-0.349" upper="0.349" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="mfproximal"> |
|
<inertial> |
|
<mass value="0.014" /> |
|
<origin xyz="0 0 0.0225" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="proximal_visual"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="proximal_collision_geom"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="MFJ3" type="revolute"> |
|
<parent link="mfknuckle" /> |
|
<child link="mfproximal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="mfmiddle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.0125" /> |
|
<mass value="0.012" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="middle_visual"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="middle_collision_geom"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="MFJ2" type="revolute"> |
|
<parent link="mfproximal" /> |
|
<child link="mfmiddle" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.045" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="mfdistal"> |
|
<inertial> |
|
<mass value="0.010" /> |
|
<origin xyz="0 0 0.013" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_visual"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
|
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_collision_geom"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="MFJ1" type="revolute"> |
|
<parent link="mfmiddle" /> |
|
<child link="mfdistal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.025" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="rfknuckle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
|
|
<mass value="0.008" /> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0005" /> |
|
<geometry name="knuckle_visual"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
<material name="LightGrey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0005" /> |
|
<geometry name="knuckle_collision_geom"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="RFJ4" type="revolute"> |
|
<parent link="palm" /> |
|
<child link="rfknuckle" /> |
|
|
|
<origin rpy="0 0 0" xyz="-0.011 0 0.095" /> |
|
<axis xyz="0 -1 0" /> |
|
<limit effort="100" lower="-0.349" upper="0.349" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="rfproximal"> |
|
<inertial> |
|
<mass value="0.014" /> |
|
<origin xyz="0 0 0.0225" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="proximal_visual"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="proximal_collision_geom"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="RFJ3" type="revolute"> |
|
<parent link="rfknuckle" /> |
|
<child link="rfproximal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="rfmiddle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.0125" /> |
|
<mass value="0.012" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="middle_visual"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="middle_collision_geom"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="RFJ2" type="revolute"> |
|
<parent link="rfproximal" /> |
|
<child link="rfmiddle" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.045" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="rfdistal"> |
|
<inertial> |
|
<mass value="0.010" /> |
|
<origin xyz="0 0 0.013" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_visual"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
|
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_collision_geom"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="RFJ1" type="revolute"> |
|
<parent link="rfmiddle" /> |
|
<child link="rfdistal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.025" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="lfmetacarpal"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.04" /> |
|
<mass value="0.075" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<geometry name="lfmetacarpal_visual"> |
|
<mesh filename="package://meshes/lfmetacarpal.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 0.0" /> |
|
<geometry name="lfmetacarpal_collision_geom"> |
|
<mesh filename="package://meshes/lfmetacarpal.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="LFJ5" type="revolute"> |
|
<parent link="palm" /> |
|
<child link="lfmetacarpal" /> |
|
<origin rpy="0 0 0" xyz="-0.033 0 0.02071" /> |
|
<axis xyz="-0.573576436 0 -0.819152044" /> |
|
<limit effort="100" lower="0" upper="0.785" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="lfknuckle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.06579" /> |
|
<mass value="0.008" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="knuckle_visual"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
<material name="LightGrey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="knuckle_collision_geom"> |
|
<mesh filename="package://meshes/knuckle.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="LFJ4" type="revolute"> |
|
<parent link="lfmetacarpal" /> |
|
<child link="lfknuckle" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.06579" /> |
|
<axis xyz="0 -1 0" /> |
|
<limit effort="100" lower="-0.43633231299858238" upper="0.43633231299858238" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="lfproximal"> |
|
<inertial> |
|
<mass value="0.014" /> |
|
<origin xyz="0 0 0.0225" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="proximal_visual"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="proximal_collision_geom"> |
|
<mesh filename="package://meshes/F3.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="LFJ3" type="revolute"> |
|
<parent link="lfknuckle" /> |
|
<child link="lfproximal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="lfmiddle"> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0 0 0.0125" /> |
|
<mass value="0.012" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="middle_visual"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="middle_collision_geom"> |
|
<mesh filename="package://meshes/F2.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="LFJ2" type="revolute"> |
|
<parent link="lfproximal" /> |
|
<child link="lfmiddle" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.045" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="lfdistal"> |
|
<inertial> |
|
<mass value="0.010" /> |
|
<origin xyz="0 0 0.013" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.0" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_visual"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
<material name="Grey" /> |
|
</visual> |
|
|
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="distal_collision_geom"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="LFJ1" type="revolute"> |
|
<parent link="lfmiddle" /> |
|
<child link="lfdistal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.025" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="0" upper="1.57079632679" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="thbase"> |
|
<inertial> |
|
<mass value="0.010" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="thbase_visual"> |
|
<box size="0.001 0.001 0.001" /> |
|
</geometry> |
|
<material name="shadow_thbase_material"> |
|
<color rgba="0.5 0.5 0.5 1.0" /> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="thbase_collision_geom"> |
|
<box size="0.001 0.001 0.001" /> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="THJ5" type="revolute"> |
|
<parent link="palm" /> |
|
<child link="thbase" /> |
|
<origin rpy="0 0.785398163397 0" xyz="0.034 0.0085 0.029" /> |
|
<axis xyz="0 0 1.0" /> |
|
<limit effort="100" lower="-1.047" upper="1.047" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="thproximal"> |
|
<inertial> |
|
<mass value="0.016" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.019" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="thproximal_visual"> |
|
<mesh filename="package://meshes/TH3_z.obj"/> |
|
</geometry> |
|
<material name="shadow_thproximal_material"> |
|
<color rgba="0.2 0.2 0.2 1.0" /> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="thproximal_collision_geom"> |
|
<mesh filename="package://meshes/TH3_z.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="THJ4" type="revolute"> |
|
<parent link="thbase" /> |
|
<child link="thproximal" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<axis xyz="-1.0 0 0" /> |
|
<limit effort="100" lower="0" upper="1.222" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="thhub"> |
|
<inertial> |
|
<mass value="0.002" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="thhub_visual"> |
|
<box size="0.001 0.001 0.001" /> |
|
</geometry> |
|
<material name="shadow_thhub_material"> |
|
<color rgba="0.7 0.7 0.7 1.0" /> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="thhub_collision_geom"> |
|
<box size="0.001 0.001 0.001" /> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="THJ3" type="revolute"> |
|
<parent link="thproximal" /> |
|
<child link="thhub" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.038" /> |
|
<axis xyz="-1 0 0" /> |
|
<limit effort="100" lower="-0.209" upper="0.209" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="thmiddle"> |
|
<inertial> |
|
<mass value="0.016" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.016" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0" /> |
|
<geometry name="thmiddle_visual"> |
|
<mesh filename="package://meshes/TH2_z.obj"/> |
|
</geometry> |
|
<material name="shadow_thmiddle_material"> |
|
<color rgba="0.2 0.2 0.2 1.0" /> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0 0.0" /> |
|
<geometry name="thmiddle_collision_geom"> |
|
<mesh filename="package://meshes/TH2_z.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="THJ2" type="revolute"> |
|
<parent link="thhub" /> |
|
<child link="thmiddle" /> |
|
<origin rpy="0 0 0" xyz="0 0 0" /> |
|
<axis xyz="0 1 0" /> |
|
<limit effort="100" lower="-0.5237" upper="0.5237" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
<link name="thdistal"> |
|
<inertial> |
|
<mass value="0.016" /> |
|
<origin rpy="0 0 0" xyz="0 0 0.01375" /> |
|
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" /> |
|
</inertial> |
|
<visual> |
|
<origin rpy="0 0 3.1415" xyz="0 0.002 0.0025" /> |
|
<geometry name="thdistal_visual"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
<material name="shadow_thmiddle_material"> |
|
<color rgba="0.2 0.2 0.2 1.0" /> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 3.1415" xyz="0 0.002 0.0025" /> |
|
<geometry name="thmiddle_collision_geom"> |
|
<mesh filename="package://meshes/F1.obj"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="THJ1" type="revolute"> |
|
<parent link="thmiddle" /> |
|
<child link="thdistal" /> |
|
<origin rpy="0 0 -1.570796327" xyz="0 0 0.032" /> |
|
<axis xyz="0 -1 0" /> |
|
<limit effort="100" lower="0.0" upper="1.571" velocity="1.0" /> |
|
<dynamics damping="50.5" /> |
|
</joint> |
|
</robot> |
|
|