Skip to content
Snippets Groups Projects
Commit 7be9734c authored by Wolfgang Merkt's avatar Wolfgang Merkt
Browse files

[panda_description] Update inertials from upstream franka_description Gazebo URDF

Created the Gazebo URDF from upstream franka_description package and
then manually merged the inertials and new TCP frame into our packaged
URDF. Should fix #122

Note: There are two types of URDFs in the upstream repository. One also
has simplified, larger collision shapes. Since we possibly want to
simulate using the URDFs here, I kept the configuration using the convex
meshes rather than primitive shapes.
parent 37025761
No related branches found
No related tags found
No related merge requests found
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /opt/ros/kinetic/share/moveit_resources/panda_description/urdf/panda.urdf | --> <!-- | This document was autogenerated by xacro from franka_ros/franka_description/robots/panda/panda.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<robot name="panda" xmlns:xacro="http://www.ros.org/wiki/xacro"> <robot name="panda" xmlns:xacro="http://www.ros.org/wiki/xacro">
...@@ -15,13 +15,13 @@ ...@@ -15,13 +15,13 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link0.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link0.stl" />
</geometry> </geometry>
</collision> </collision>
</link>
<link name="panda_link1">
<inertial> <inertial>
<mass value="0"/> <origin rpy="0 0 0" xyz="-0.041018 -0.00014 0.049974"/>
<origin rpy="0 0 0" xyz="0 0 0"/> <mass value="0.629769"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> <inertia ixx="0.00315" ixy="8.2904e-07" ixz="0.00015" iyy="0.00388" iyz="8.2299e-06" izz="0.004285"/>
</inertial> </inertial>
</link>
<link name="panda_link1">
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link1.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link1.dae" />
...@@ -32,21 +32,22 @@ ...@@ -32,21 +32,22 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link1.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link1.stl" />
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="0.003875 0.002081 -0.04762"/>
<mass value="4.970684"/>
<inertia ixx="0.70337" ixy="-0.000139" ixz="0.006772" iyy="0.70661" iyz="0.019169" izz="0.009117"/>
</inertial>
</link> </link>
<joint name="panda_joint1" type="revolute"> <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"/>
<origin rpy="0 0 0" xyz="0 0 0.333" /> <parent link="panda_link0"/>
<parent link="panda_link0" /> <child link="panda_link1"/>
<child link="panda_link1" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="87.0" lower="-2.8973" upper="2.8973" velocity="2.175"/>
<limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.3925" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link2"> <link name="panda_link2">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link2.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link2.dae" />
...@@ -57,21 +58,22 @@ ...@@ -57,21 +58,22 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link2.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link2.stl" />
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003141 -0.02872 0.003495"/>
<mass value="0.646926"/>
<inertia ixx="0.007962" ixy="-0.003925" ixz="0.010254" iyy="0.02811" iyz="0.000704" izz="0.025995"/>
</inertial>
</link> </link>
<joint name="panda_joint2" type="revolute"> <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.5707963267948966 0 0" xyz="0 0 0"/>
<origin rpy="-1.57079632679 0 0" xyz="0 0 0" /> <parent link="panda_link1"/>
<parent link="panda_link1" /> <child link="panda_link2"/>
<child link="panda_link2" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="87.0" lower="-1.7628" upper="1.7628" velocity="2.175"/>
<limit effort="87" lower="-1.8326" upper="1.8326" velocity="2.3925" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link3"> <link name="panda_link3">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link3.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link3.dae" />
...@@ -82,46 +84,48 @@ ...@@ -82,46 +84,48 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link3.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link3.stl" />
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="2.7518e-02 3.9252e-02 -6.6502e-02"/>
<mass value="3.228604"/>
<inertia ixx="0.037242" ixy="-0.004761" ixz="-0.011396" iyy="0.036155" iyz="-0.012805" izz="0.01083"/>
</inertial>
</link> </link>
<joint name="panda_joint3" type="revolute"> <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.5707963267948966 0 0" xyz="0 -0.316 0"/>
<origin rpy="1.57079632679 0 0" xyz="0 -0.316 0" /> <parent link="panda_link2"/>
<parent link="panda_link2" /> <child link="panda_link3"/>
<child link="panda_link3" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="87.0" lower="-2.8973" upper="2.8973" velocity="2.175"/>
<limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.3925" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link4"> <link name="panda_link4">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link4.dae" /> <mesh filename="package://franka_description/meshes/visual/link4.dae"/>
</geometry> </geometry>
</visual> </visual>
<collision> <collision>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link4.stl" /> <mesh filename="package://franka_description/meshes/collision/link4.stl"/>
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="-5.317e-02 1.04419e-01 2.7454e-02"/>
<mass value="3.587895"/>
<inertia ixx="0.025853" ixy="0.007796" ixz="-0.001332" iyy="0.019552" iyz="0.008641" izz="0.028323"/>
</inertial>
</link> </link>
<joint name="panda_joint4" type="revolute"> <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.0175" /> <origin rpy="1.5707963267948966 0 0" xyz="0.0825 0 0"/>
<origin rpy="1.57079632679 0 0" xyz="0.0825 0 0" /> <parent link="panda_link3"/>
<parent link="panda_link3" /> <child link="panda_link4"/>
<child link="panda_link4" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="87.0" lower="-3.0718" upper="-0.0698" velocity="2.175"/>
<limit effort="87" lower="-3.1416" upper="0.0873" velocity="2.3925" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link5"> <link name="panda_link5">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link5.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link5.dae" />
...@@ -132,21 +136,22 @@ ...@@ -132,21 +136,22 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link5.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link5.stl" />
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="-1.1953e-02 4.1065e-02 -3.8437e-02"/>
<mass value="1.225946"/>
<inertia ixx="0.035549" ixy="-0.002117" ixz="-0.004037" iyy="0.029474" iyz="0.000229" izz="0.008627"/>
</inertial>
</link> </link>
<joint name="panda_joint5" type="revolute"> <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.5707963267948966 0 0" xyz="-0.0825 0.384 0"/>
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0" /> <parent link="panda_link4"/>
<parent link="panda_link4" /> <child link="panda_link5"/>
<child link="panda_link5" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="12.0" lower="-2.8973" upper="2.8973" velocity="2.61"/>
<limit effort="12" lower="-2.9671" upper="2.9671" velocity="2.8710" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link6"> <link name="panda_link6">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link6.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link6.dae" />
...@@ -157,21 +162,22 @@ ...@@ -157,21 +162,22 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link6.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link6.stl" />
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="6.0149e-02 -1.4117e-02 -1.0517e-02"/>
<mass value="1.666555"/>
<inertia ixx="0.001964" ixy="0.000109" ixz="-0.001158" iyy="0.004354" iyz="0.000341" izz="0.005433"/>
</inertial>
</link> </link>
<joint name="panda_joint6" type="revolute"> <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.5707963267948966 0 0" xyz="0 0 0"/>
<origin rpy="1.57079632679 0 0" xyz="0 0 0" /> <parent link="panda_link5"/>
<parent link="panda_link5" /> <child link="panda_link6"/>
<child link="panda_link6" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="12.0" lower="-0.0175" upper="3.7525" velocity="2.61"/>
<limit effort="12" lower="-0.0873" upper="3.8223" velocity="2.8710" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link7"> <link name="panda_link7">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link7.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link7.dae" />
...@@ -182,14 +188,20 @@ ...@@ -182,14 +188,20 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link7.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/link7.stl" />
</geometry> </geometry>
</collision> </collision>
<inertial>
<origin rpy="0 0 0" xyz="1.0517e-02 -4.252e-03 6.1597e-02"/>
<mass value="0.735522"/>
<inertia ixx="0.012516" ixy="-0.000428" ixz="-0.001196" iyy="0.010027" iyz="-0.000741" izz="0.004815"/>
</inertial>
</link> </link>
<joint name="panda_joint7" type="revolute"> <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.5707963267948966 0 0" xyz="0.088 0 0"/>
<origin rpy="1.57079632679 0 0" xyz="0.088 0 0" /> <parent link="panda_link6"/>
<parent link="panda_link6" /> <child link="panda_link7"/>
<child link="panda_link7" /> <axis xyz="0 0 1"/>
<axis xyz="0 0 1" /> <limit effort="12.0" lower="-2.8973" upper="2.8973" velocity="2.61"/>
<limit effort="12" lower="-2.9671" upper="2.9671" velocity="2.8710" /> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint> </joint>
<link name="panda_link8"> <link name="panda_link8">
<inertial> <inertial>
...@@ -199,22 +211,16 @@ ...@@ -199,22 +211,16 @@
</inertial> </inertial>
</link> </link>
<joint name="panda_joint8" type="fixed"> <joint name="panda_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107" /> <origin rpy="0 0 0" xyz="0 0 0.107"/>
<parent link="panda_link7" /> <parent link="panda_link7"/>
<child link="panda_link8" /> <child link="panda_link8"/>
<axis xyz="0 0 0" />
</joint> </joint>
<joint name="panda_hand_joint" type="fixed"> <joint name="panda_hand_joint" type="fixed">
<parent link="panda_link8" /> <parent link="panda_link8"/>
<child link="panda_hand" /> <child link="panda_hand"/>
<origin rpy="0 0 -0.785398163397" xyz="0 0 0" /> <origin rpy="0 0 -0.7853981633974483" xyz="0 0 0"/>
</joint> </joint>
<link name="panda_hand"> <link name="panda_hand">
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/hand.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/hand.dae" />
...@@ -225,56 +231,122 @@ ...@@ -225,56 +231,122 @@
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/hand.stl" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/hand.stl" />
</geometry> </geometry>
</collision> </collision>
</link>
<link name="panda_leftfinger">
<inertial> <inertial>
<origin rpy="0 0 0" xyz="-0.01 0 0.03"/>
<mass value="0.73"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.0025" iyz="0" izz="0.0017"/>
</inertial>
</link>
<!-- Define the hand_tcp frame -->
<link name="panda_hand_tcp">
<inertial>
<mass value="0"/> <mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial> </inertial>
</link>
<joint name="panda_hand_tcp_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.1034"/>
<parent link="panda_hand"/>
<child link="panda_hand_tcp"/>
</joint>
<link name="panda_leftfinger">
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/finger.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/finger.dae" />
</geometry> </geometry>
</visual> </visual>
<!-- screw mount -->
<collision> <collision>
<origin rpy="0 0 0" xyz="0 18.5e-3 11e-3"/>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/finger.stl" /> <box size="22e-3 15e-3 20e-3"/>
</geometry>
</collision>
<!-- cartriage sledge -->
<collision>
<origin rpy="0 0 0" xyz="0 6.8e-3 2.2e-3"/>
<geometry>
<box size="22e-3 8.8e-3 3.8e-3"/>
</geometry>
</collision>
<!-- diagonal finger -->
<collision>
<origin rpy="0.5235987755982988 0 0" xyz="0 15.9e-3 28.35e-3"/>
<geometry>
<box size="17.5e-3 7e-3 23.5e-3"/>
</geometry>
</collision>
<!-- rubber tip with which to grasp -->
<collision>
<origin rpy="0 0 0" xyz="0 7.58e-3 45.25e-3"/>
<geometry>
<box size="17.5e-3 15.2e-3 18.5e-3"/>
</geometry> </geometry>
</collision> </collision>
</link>
<link name="panda_rightfinger">
<inertial> <inertial>
<mass value="0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0"/> <mass value="0.015"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> <inertia ixx="2.3749999999999997e-06" ixy="0" ixz="0" iyy="2.3749999999999997e-06" iyz="0" izz="7.5e-07"/>
</inertial> </inertial>
</link>
<link name="panda_rightfinger">
<visual> <visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0" /> <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/finger.dae" /> <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/finger.dae" />
</geometry> </geometry>
</visual> </visual>
<!-- screw mount -->
<collision>
<origin rpy="0 0 0" xyz="0 -18.5e-3 11e-3"/>
<geometry>
<box size="22e-3 15e-3 20e-3"/>
</geometry>
</collision>
<!-- cartriage sledge -->
<collision>
<origin rpy="0 0 0" xyz="0 -6.8e-3 2.2e-3"/>
<geometry>
<box size="22e-3 8.8e-3 3.8e-3"/>
</geometry>
</collision>
<!-- diagonal finger -->
<collision> <collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0" /> <origin rpy="-0.5235987755982988 0 0" xyz="0 -15.9e-3 28.35e-3"/>
<geometry> <geometry>
<mesh filename="package://example-robot-data/robots/panda_description/meshes/collision/finger.stl" /> <box size="17.5e-3 7e-3 23.5e-3"/>
</geometry> </geometry>
</collision> </collision>
<!-- rubber tip with which to grasp -->
<collision>
<origin rpy="0 0 0" xyz="0 -7.58e-3 45.25e-3"/>
<geometry>
<box size="17.5e-3 15.2e-3 18.5e-3"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.015"/>
<inertia ixx="2.3749999999999997e-06" ixy="0" ixz="0" iyy="2.3749999999999997e-06" iyz="0" izz="7.5e-07"/>
</inertial>
</link> </link>
<joint name="panda_finger_joint1" type="prismatic"> <joint name="panda_finger_joint1" type="prismatic">
<parent link="panda_hand" /> <parent link="panda_hand"/>
<child link="panda_leftfinger" /> <child link="panda_leftfinger"/>
<origin rpy="0 0 0" xyz="0 0 0.0584" /> <origin rpy="0 0 0" xyz="0 0 0.0584"/>
<axis xyz="0 1 0" /> <axis xyz="0 1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2" /> <limit effort="100" lower="0.0" upper="0.04" velocity="0.2"/>
<dynamics damping="0.3"/>
</joint> </joint>
<joint name="panda_finger_joint2" type="prismatic"> <joint name="panda_finger_joint2" type="prismatic">
<parent link="panda_hand" /> <parent link="panda_hand"/>
<child link="panda_rightfinger" /> <child link="panda_rightfinger"/>
<origin rpy="0 0 0" xyz="0 0 0.0584" /> <origin rpy="0 0 0" xyz="0 0 0.0584"/>
<axis xyz="0 -1 0" /> <axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2" /> <limit effort="100" lower="0.0" upper="0.04" velocity="0.2"/>
<mimic joint="panda_finger_joint1" /> <mimic joint="panda_finger_joint1"/>
<dynamics damping="0.3"/>
</joint> </joint>
</robot> </robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment