|
<?xml version="1.0" ?> |
|
|
|
|
|
|
|
|
|
|
|
<robot name="kinova" xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz" xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint" xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model" xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable" xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:xi="http://www.w3.org/2001/XInclude"> |
|
<link name="world"> </link> |
|
|
|
<link name="platform"> |
|
<visual> |
|
|
|
<origin rpy="0 0 0" xyz="0 0 0.25"/> |
|
<geometry> |
|
<box size="0.845 0.27 0.5"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 0.25"/> |
|
<geometry> |
|
<box size="0.845 0.27 0.5"/> |
|
</geometry> |
|
</collision> |
|
</link> |
|
<joint name="platform_joint_world" type="fixed"> |
|
<parent link="world"/> |
|
<child link="platform"/> |
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
</joint> |
|
|
|
<link name="kinova_link_base"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/base.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 0.078375"/> |
|
<geometry> |
|
<cylinder length="0.15675" radius="0.04125" /> |
|
</geometry> |
|
</collision> |
|
|
|
</link> |
|
<joint name="kinova_joint_platform" type="fixed"> |
|
<parent link="platform"/> |
|
<child link="kinova_link_base"/> |
|
<origin rpy="0 0 0" xyz="0.314 0 0.5"/> |
|
</joint> |
|
|
|
<joint name="kinova_link_base_to_kinova_link_base_inertia" type="fixed"> |
|
<parent link="kinova_link_base"/> |
|
<child link="kinova_link_base_inertia"/> |
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
</joint> |
|
|
|
<link name="kinova_link_base_inertia"> |
|
<inertial> |
|
<mass value="0.46784"/> |
|
<origin rpy="0 0 0" xyz="0 0 0.1255"/> |
|
<inertia ixx="0.000951270861568" ixy="0" ixz="0" iyy="0.000951270861568" iyz="0" izz="0.000374272"/> |
|
</inertial> |
|
</link> |
|
<link name="kinova_link_1"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/shoulder.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/ring_big.STL"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.0187"/> |
|
<geometry> |
|
<cylinder length="0.0374" radius="0.041"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 -0.0205 -0.07994"/> |
|
<geometry> |
|
<box size="0.082 0.041 0.08488"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="1.57079632679 0 0" xyz="0 -0.0205 -0.119"/> |
|
<geometry> |
|
<cylinder length="0.041" radius="0.041"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.7477"/> |
|
<origin xyz="0 -0.002 -0.0605"/> |
|
<inertia ixx="0.00152031725204" ixy="0" ixz="0" iyy="0.00152031725204" iyz="0" izz="0.00059816"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_1" type="revolute"> |
|
<parent link="kinova_link_base"/> |
|
<child link="kinova_link_1"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="30.5" lower="-62.8318530718" upper="62.8318530718" velocity="15"/> |
|
|
|
<origin rpy="0 3.14159265359 0" xyz="0 0 0.15675"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="kinova_link_2"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/arm.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/ring_big.STL"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.0215"/> |
|
<geometry> |
|
<cylinder length="0.043" radius="0.0415"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 -0.204875 -0.0325"/> |
|
<geometry> |
|
<box size="0.0825 0.40975 0.0215"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 -0.204875 -0.0215"/> |
|
<geometry> |
|
<box size="0.0825 0.26975 0.0325"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 -0.40975 -0.0215"/> |
|
<geometry> |
|
<cylinder length="0.043" radius="0.0415"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.99"/> |
|
<origin xyz="0 -0.2065 -0.01"/> |
|
<inertia ixx="0.010502207991" ixy="0" ixz="0" iyy="0.000792" iyz="0" izz="0.010502207991"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_2" type="revolute"> |
|
<parent link="kinova_link_1"/> |
|
<child link="kinova_link_2"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="30.5" lower="-62.8318530718" upper="62.8318530718" velocity="15"/> |
|
|
|
<origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.0016 -0.11875"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="kinova_link_3"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/forearm.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/ring_big.STL"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.0215"/> |
|
<geometry> |
|
<cylinder length="0.043" radius="0.0415"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0.053 -0.0215"/> |
|
<geometry> |
|
<box size="0.0825 0.106 0.043"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="1.57079632679 0 0" xyz="0 0.15525 -0.0115"/> |
|
<geometry> |
|
<cylinder length="0.1035" radius="0.0315"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.6763"/> |
|
<origin xyz="0 0.081 -0.0086"/> |
|
<inertia ixx="0.00142022431908" ixy="0" ixz="0" iyy="0.000304335" iyz="0" izz="0.00142022431908"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_3" type="revolute"> |
|
<parent link="kinova_link_2"/> |
|
<child link="kinova_link_3"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="30.5" lower="-62.8318530718" upper="62.8318530718" velocity="15"/> |
|
|
|
<origin rpy="0 3.14159265359 0" xyz="0 -0.410 0"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="kinova_link_4"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/wrist_spherical_1.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/ring_small.STL"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.025"/> |
|
<geometry> |
|
<cylinder length="0.050" radius="0.0315"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0.0157 -0.0753"/> |
|
<geometry> |
|
<box size="0.063 0.0315 0.056"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="1.57079632679 0 0" xyz="0 0.024 -0.10362"/> |
|
<geometry> |
|
<cylinder length="0.048" radius="0.0315"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.463"/> |
|
<origin xyz="0 0.0028848942 -0.0541932613"/> |
|
<inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="0.0004321316048" iyz="0" izz="9.26e-05"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_4" type="revolute"> |
|
<parent link="kinova_link_3"/> |
|
<child link="kinova_link_4"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="6.8" lower="-62.8318530718" upper="6.28318530718" velocity="15"/> |
|
|
|
<origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.2073 -0.0114"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="kinova_link_5"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/wrist_spherical_2.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/ring_small.STL"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.024"/> |
|
<geometry> |
|
<cylinder length="0.048" radius="0.0315"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0.028 -0.01575"/> |
|
<geometry> |
|
<box size="0.063 0.056 0.0315"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="1.57079632679 0 0" xyz="0 0.07862 0"/> |
|
<geometry> |
|
<cylinder length="0.050" radius="0.0315"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.463"/> |
|
<origin xyz="0 0.0497208855 -0.0028562765"/> |
|
<inertia ixx="0.0004321316048" ixy="0" ixz="0" iyy="9.26e-05" iyz="0" izz="0.0004321316048"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_5" type="revolute"> |
|
<parent link="kinova_link_4"/> |
|
<child link="kinova_link_5"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="6.8" lower="-6.28318530718" upper="62.8318530718" velocity="15"/> |
|
|
|
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 -0.10375"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="kinova_link_6"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/hand_3finger.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/ring_small.STL"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.024"/> |
|
<geometry> |
|
<cylinder length="0.048" radius="0.0315"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0.43 0 0" xyz="0 0.0175 -0.06"/> |
|
<geometry> |
|
<cylinder length="0.0775" radius="0.02625"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0.43 0 0" xyz="0 0.0175 -0.0575"/> |
|
<geometry> |
|
<cylinder length="0.0975" radius="0.021"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="-0.435 0 0.62" xyz="0.0175 -0.0175 -0.06"/> |
|
<geometry> |
|
<cylinder length="0.0775" radius="0.02625"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="-0.435 0 0.62" xyz="0.0175 -0.0175 -0.0575"/> |
|
<geometry> |
|
<cylinder length="0.0975" radius="0.021"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="-0.435 0 -0.62" xyz="-0.0175 -0.0175 -0.06"/> |
|
<geometry> |
|
<cylinder length="0.0775" radius="0.02625"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="-0.435 0 -0.62" xyz="-0.0175 -0.0175 -0.0575"/> |
|
<geometry> |
|
<cylinder length="0.0975" radius="0.021"/> |
|
</geometry> |
|
</collision> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0 0 -0.0550"/> |
|
<geometry> |
|
<box size="0.050 0.032 0.1075"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="1.327"/> |
|
|
|
<origin xyz="0 0 -0.06"/> |
|
<inertia ixx="0.0004403232387" ixy="0" ixz="0" iyy="0.0004403232387" iyz="0" izz="0.0007416"/> |
|
</inertial> |
|
</link> |
|
|
|
<joint name="kinova_joint_6" type="revolute"> |
|
<parent link="kinova_link_5"/> |
|
<child link="kinova_link_6"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="6.8" lower="-62.8318530718" upper="62.8318530718" velocity="15"/> |
|
|
|
<origin rpy="-1.57079632679 0 3.14159265359" xyz="0 0.10375 0"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
|
|
<link name="kinova_end_effector"> |
|
|
|
|
|
<visual> |
|
<geometry> |
|
<box size="0.0001 0.0001 0.0001"/> |
|
</geometry> |
|
</visual> |
|
<collision> |
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.1"/> |
|
<geometry> |
|
<box size="0.00001 0.00001 0.00001"/> |
|
</geometry> |
|
</collision> |
|
<inertial> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<mass value="0.01"/> |
|
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_end_effector" type="fixed"> |
|
|
|
<parent link="kinova_link_6"/> |
|
<child link="kinova_end_effector"/> |
|
<axis xyz="0 0 0"/> |
|
<limit effort="2000" lower="0" upper="0" velocity="1"/> |
|
<origin rpy="3.14159265359 0 0" xyz="0 0 -0.1600"/> |
|
</joint> |
|
<link name="kinova_link_finger_1"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/finger_proximal.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0.025 -0.01147 0.0"/> |
|
<geometry> |
|
<box size="0.05 0.02294 0.02294"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.01"/> |
|
<origin xyz="0.022 0 0"/> |
|
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_finger_1" type="revolute"> |
|
<parent link="kinova_link_6"/> |
|
<child link="kinova_link_finger_1"/> |
|
<axis xyz="0 0 1"/> |
|
<origin rpy="-1.570796327 0.649262481663582 1.35961148639407" xyz="0.00279 0.03126 -0.11467"/> |
|
<limit effort="2000" lower="0" upper="2" velocity="1"/> |
|
</joint> |
|
<link name="kinova_link_finger_tip_1"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/finger_distal.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0.025 -0.01 0.0"/> |
|
<geometry> |
|
<box size="0.045 0.022 0.02294"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.01"/> |
|
<origin xyz="0.022 0 0"/> |
|
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_finger_tip_1" type="fixed"> |
|
<parent link="kinova_link_finger_1"/> |
|
<child link="kinova_link_finger_tip_1"/> |
|
<axis xyz="0 0 1"/> |
|
<origin rpy="0 0 0" xyz="0.044 -0.003 0"/> |
|
<limit effort="2000" lower="0" upper="2" velocity="1"/> |
|
</joint> |
|
<link name="kinova_link_finger_2"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/finger_proximal.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0.025 -0.01147 0.0"/> |
|
<geometry> |
|
<box size="0.05 0.02294 0.02294"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.01"/> |
|
<origin xyz="0.022 0 0"/> |
|
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_finger_2" type="revolute"> |
|
<parent link="kinova_link_6"/> |
|
<child link="kinova_link_finger_2"/> |
|
<axis xyz="0 0 1"/> |
|
<origin rpy="-1.570796327 0.649262481663582 -1.38614049188413" xyz="0.02226 -0.02707 -0.11482"/> |
|
<limit effort="2000" lower="0" upper="2" velocity="1"/> |
|
</joint> |
|
<link name="kinova_link_finger_tip_2"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/finger_distal.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0.025 -0.01 0.0"/> |
|
<geometry> |
|
<box size="0.045 0.022 0.02294"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.01"/> |
|
<origin xyz="0.022 0 0"/> |
|
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_finger_tip_2" type="fixed"> |
|
<parent link="kinova_link_finger_2"/> |
|
<child link="kinova_link_finger_tip_2"/> |
|
<axis xyz="0 0 1"/> |
|
<origin rpy="0 0 0" xyz="0.044 -0.003 0"/> |
|
<limit effort="2000" lower="0" upper="2" velocity="1"/> |
|
</joint> |
|
<link name="kinova_link_finger_3"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/finger_proximal.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0.025 -0.01147 0.0"/> |
|
<geometry> |
|
<box size="0.05 0.02294 0.02294"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.01"/> |
|
<origin xyz="0.022 0 0"/> |
|
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_finger_3" type="revolute"> |
|
<parent link="kinova_link_6"/> |
|
<child link="kinova_link_finger_3"/> |
|
<axis xyz="0 0 1"/> |
|
<origin rpy="-1.570796327 0.649262481663582 -1.75545216211587" xyz="-0.02226 -0.02707 -0.11482"/> |
|
<limit effort="2000" lower="0" upper="2" velocity="1"/> |
|
</joint> |
|
<link name="kinova_link_finger_tip_3"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="../meshes/finger_distal.dae"/> |
|
</geometry> |
|
<material name="carbon_fiber"> |
|
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> |
|
</material> |
|
</visual> |
|
<collision> |
|
<origin rpy="0 0 0" xyz="0.025 -0.01 0.0"/> |
|
<geometry> |
|
<box size="0.045 0.022 0.02294"/> |
|
</geometry> |
|
</collision> |
|
--> |
|
|
|
<inertial> |
|
<mass value="0.01"/> |
|
<origin xyz="0.022 0 0"/> |
|
<inertia ixx="7.8999684e-07" ixy="0" ixz="0" iyy="7.8999684e-07" iyz="0" izz="8e-08"/> |
|
</inertial> |
|
</link> |
|
<joint name="kinova_joint_finger_tip_3" type="fixed"> |
|
<parent link="kinova_link_finger_3"/> |
|
<child link="kinova_link_finger_tip_3"/> |
|
<axis xyz="0 0 1"/> |
|
<origin rpy="0 0 0" xyz="0.044 -0.003 0"/> |
|
<limit effort="2000" lower="0" upper="2" velocity="1"/> |
|
</joint> |
|
</robot> |
|
|