diff --git a/robots/talos_small.urdf b/robots/talos_reduced.urdf similarity index 72% rename from robots/talos_small.urdf rename to robots/talos_reduced.urdf index e1e52213822070781ce82bae9d6688030131c922..9ff31a7b6be2639467c5e1f0197ce35b6b4efbce 100644 --- a/robots/talos_small.urdf +++ b/robots/talos_reduced.urdf @@ -1,6 +1,6 @@ <?xml version="1.0" ?> <!-- =================================================================================== --> -<!-- | This document was autogenerated by xacro from talos_small.urdf.xacro | --> +<!-- | This document was autogenerated by xacro from talos_full.urdf.xacro | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- =================================================================================== --> <!-- @@ -13,10 +13,6 @@ Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. --> <robot name="talos" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro"> - <!-- - Talos configuration without the grippers - - --> <!--File includes--> <!--Constant parameters--> <!--File includes--> @@ -32,7 +28,8 @@ <!--File includes--> <!--Constant parameters--> <!--Constant parameters--> - <!-- <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> --> + <!--File includes--> + <!-- VIRTUAL (mimic) JOINTS --> <!-- 0.45deg --> <!--************************--> <!-- TORSO_2 (TILT) --> @@ -292,8 +289,8 @@ <!-- <visual> <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/sensors/orbbec/orbbec.STL"/> + <geometry> + <mesh filename="package://talos_description/meshes/sensors/orbbec/orbbec.STL"/> </geometry> <material name="DarkGrey"> <color rgba="0.5 0.5 0.5 1"/> @@ -1318,10 +1315,716 @@ <child link="wrist_left_ft_tool_link"/> <origin rpy="0 0 4.71238898038" xyz="0 0 -0.012725"/> </joint> - <!-- - <xacro:talos_gripper name="gripper_left" parent="wrist_left_ft_tool_link" reflect="1" /> - <xacro:talos_gripper name="gripper_right" parent="wrist_right_ft_tool_link" reflect="-1" /> - --> + <link name="gripper_left_base_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00534 0.00362 -0.02357"/> + <mass value="0.61585"/> + <inertia ixx="0.00047200000" ixy="-0.00000800000" ixz="0.00003500000" iyy="0.00052100000" iyz="0.00000000000" izz="0.00069000000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/base_link.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/base_link_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_base_link_joint" type="fixed"> + <parent link="wrist_left_ft_tool_link"/> + <child link="gripper_left_base_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.02875"/> + <axis xyz="0 0 0"/> + </joint> + <link name="gripper_left_motor_double_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.02270 0.01781 -0.00977"/> + <mass value="0.16889"/> + <!-- In order for Gazebo not to explode we needed to add these 0.001 values to the diagonal, + also the tool pal_dynamics InertiaMassVisualization gave NaN on the computation of the inertia box --> + <inertia ixx="0.001159" ixy="-0.00007000000" ixz="0.00003800000" iyy="0.001221" iyz="-0.00005300000" izz="0.001268"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_joint" type="revolute"> + <parent link="gripper_left_base_link"/> + <child link="gripper_left_motor_double_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.02025 -0.03"/> + <axis xyz="1 0 0"/> + <limit effort="1.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/> + <dynamics damping="1.0" friction="1.0"/> + </joint> + <link name="gripper_left_inner_double_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00056 0.03358 -0.01741"/> + <mass value="0.11922"/> + <inertia ixx="0.00009100000" ixy="0.00000100000" ixz="-0.00000100000" iyy="0.00015600000" iyz="-0.00003200000" izz="0.00012600000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_double.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_inner_double_joint" type="fixed"> + <parent link="gripper_left_base_link"/> + <child link="gripper_left_inner_double_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00525 -0.05598"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/> + <mimic joint="gripper_left_joint" multiplier="1.0" offset="0.0"/> + </joint> + <link name="gripper_left_fingertip_1_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_fingertip_1_joint" type="fixed"> + <parent link="gripper_left_inner_double_link"/> + <child link="gripper_left_fingertip_1_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.03200 0.04589 -0.06553"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_left_fingertip_2_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_fingertip_2_joint" type="fixed"> + <parent link="gripper_left_inner_double_link"/> + <child link="gripper_left_fingertip_2_link"/> + <origin rpy="0.0 0.0 0.0" xyz="-0.03200 0.04589 -0.06553"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_left_motor_single_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.02589 -0.01284 -0.00640"/> + <mass value="0.14765"/> + <inertia ixx="0.00011500000" ixy="0.00005200000" ixz="0.00002500000" iyy="0.00015300000" iyz="0.00003400000" izz="0.00019000000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_motor_single_joint" type="fixed"> + <parent link="gripper_left_base_link"/> + <child link="gripper_left_motor_single_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.02025 -0.03000"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_left_inner_single_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.03253 -0.01883"/> + <mass value="0.05356"/> + <inertia ixx="0.00004700000" ixy="-0.00000000000" ixz="-0.00000000000" iyy="0.00003500000" iyz="0.00001700000" izz="0.00002400000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_single.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_inner_single_joint" type="fixed"> + <parent link="gripper_left_base_link"/> + <child link="gripper_left_inner_single_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.00525 -0.05598"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_left_fingertip_3_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_left_fingertip_3_joint" type="fixed"> + <parent link="gripper_left_inner_single_link"/> + <child link="gripper_left_fingertip_3_link"/> + <origin rpy="0.0 0.0 3.14159265359" xyz="0.00000 -0.04589 -0.06553"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <gazebo> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_inner_double_joint"> + <joint>gripper_left_joint</joint> + <mimicJoint>gripper_left_inner_double_joint</mimicJoint> + <multiplier>1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_fingertip_1_joint"> + <joint>gripper_left_joint</joint> + <mimicJoint>gripper_left_fingertip_1_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_fingertip_2_joint"> + <joint>gripper_left_joint</joint> + <mimicJoint>gripper_left_fingertip_2_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_inner_single_joint"> + <joint>gripper_left_joint</joint> + <mimicJoint>gripper_left_inner_single_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_motor_single_joint"> + <joint>gripper_left_joint</joint> + <mimicJoint>gripper_left_motor_single_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_fingertip_3_joint"> + <joint>gripper_left_joint</joint> + <mimicJoint>gripper_left_fingertip_3_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + </gazebo> + <!-- <plugin filename="libgazebo_underactuated_finger.so" name="gazebo_${name}_underactuated"> + <actuatedJoint>${name}_joint</actuatedJoint> + <virtualJoint> + <name>${name}_inner_double_joint</name> + <scale_factor>1.0</scale_factor> + </virtualJoint> --> + <!-- <virtualJoint> + <name>${name}_fingertip_1_joint</name> + <scale_factor>-1.0</scale_factor> + </virtualJoint> + <virtualJoint> + <name>${name}_fingertip_2_joint</name> + <scale_factor>-1.0</scale_factor> + </virtualJoint> + <virtualJoint> + <name>${name}_motor_single_joint</name> + <scale_factor>1.0</scale_factor> + </virtualJoint> + <virtualJoint> + <name>${name}_fingertip_3_joint</name> + <scale_factor>-1.0</scale_factor> + </virtualJoint> --> + <!-- </plugin> --> + <gazebo reference="gripper_left_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_left_inner_double_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_left_fingertip_1_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_left_fingertip_2_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_left_motor_single_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_left_fingertip_3_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_left_base_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="gripper_left_motor_double_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_left_inner_double_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_left_fingertip_1_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="gripper_left_motor_single_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_left_inner_single_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_left_fingertip_2_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="gripper_left_fingertip_3_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <transmission name="gripper_left_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="gripper_left_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="gripper_left_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + </joint> + </transmission> + <!-- virtual mimic joints --> + <!-- <xacro:gripper_virtual_transmission name="${name}_inner_double" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_1" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_2" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_inner_single" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_motor_single" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_3" reduction="1.0"/> --> + <link name="gripper_right_base_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00534 0.00362 -0.02357"/> + <mass value="0.61585"/> + <inertia ixx="0.00047200000" ixy="-0.00000800000" ixz="0.00003500000" iyy="0.00052100000" iyz="0.00000000000" izz="0.00069000000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/base_link.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/base_link_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_base_link_joint" type="fixed"> + <parent link="wrist_right_ft_tool_link"/> + <child link="gripper_right_base_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.02875"/> + <axis xyz="0 0 0"/> + </joint> + <link name="gripper_right_motor_double_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.02270 0.01781 -0.00977"/> + <mass value="0.16889"/> + <!-- In order for Gazebo not to explode we needed to add these 0.001 values to the diagonal, + also the tool pal_dynamics InertiaMassVisualization gave NaN on the computation of the inertia box --> + <inertia ixx="0.001159" ixy="-0.00007000000" ixz="0.00003800000" iyy="0.001221" iyz="-0.00005300000" izz="0.001268"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_joint" type="revolute"> + <parent link="gripper_right_base_link"/> + <child link="gripper_right_motor_double_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.02025 -0.03"/> + <axis xyz="1 0 0"/> + <limit effort="1.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/> + <dynamics damping="1.0" friction="1.0"/> + </joint> + <link name="gripper_right_inner_double_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00056 0.03358 -0.01741"/> + <mass value="0.11922"/> + <inertia ixx="0.00009100000" ixy="0.00000100000" ixz="-0.00000100000" iyy="0.00015600000" iyz="-0.00003200000" izz="0.00012600000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_double.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_inner_double_joint" type="fixed"> + <parent link="gripper_right_base_link"/> + <child link="gripper_right_inner_double_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00525 -0.05598"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/> + <mimic joint="gripper_right_joint" multiplier="1.0" offset="0.0"/> + </joint> + <link name="gripper_right_fingertip_1_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_fingertip_1_joint" type="fixed"> + <parent link="gripper_right_inner_double_link"/> + <child link="gripper_right_fingertip_1_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.03200 0.04589 -0.06553"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_right_fingertip_2_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_fingertip_2_joint" type="fixed"> + <parent link="gripper_right_inner_double_link"/> + <child link="gripper_right_fingertip_2_link"/> + <origin rpy="0.0 0.0 0.0" xyz="-0.03200 0.04589 -0.06553"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_right_motor_single_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.02589 -0.01284 -0.00640"/> + <mass value="0.14765"/> + <inertia ixx="0.00011500000" ixy="0.00005200000" ixz="0.00002500000" iyy="0.00015300000" iyz="0.00003400000" izz="0.00019000000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_motor_single_joint" type="fixed"> + <parent link="gripper_right_base_link"/> + <child link="gripper_right_motor_single_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.02025 -0.03000"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_right_inner_single_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.03253 -0.01883"/> + <mass value="0.05356"/> + <inertia ixx="0.00004700000" ixy="-0.00000000000" ixz="-0.00000000000" iyy="0.00003500000" iyz="0.00001700000" izz="0.00002400000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_single.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_inner_single_joint" type="fixed"> + <parent link="gripper_right_base_link"/> + <child link="gripper_right_inner_single_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.00525 -0.05598"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <link name="gripper_right_fingertip_3_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="gripper_right_fingertip_3_joint" type="fixed"> + <parent link="gripper_right_inner_single_link"/> + <child link="gripper_right_fingertip_3_link"/> + <origin rpy="0.0 0.0 3.14159265359" xyz="0.00000 -0.04589 -0.06553"/> + <axis xyz="1 0 0"/> + <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/> + <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/> + </joint> + <gazebo> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_inner_double_joint"> + <joint>gripper_right_joint</joint> + <mimicJoint>gripper_right_inner_double_joint</mimicJoint> + <multiplier>1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_fingertip_1_joint"> + <joint>gripper_right_joint</joint> + <mimicJoint>gripper_right_fingertip_1_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_fingertip_2_joint"> + <joint>gripper_right_joint</joint> + <mimicJoint>gripper_right_fingertip_2_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_inner_single_joint"> + <joint>gripper_right_joint</joint> + <mimicJoint>gripper_right_inner_single_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_motor_single_joint"> + <joint>gripper_right_joint</joint> + <mimicJoint>gripper_right_motor_single_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_fingertip_3_joint"> + <joint>gripper_right_joint</joint> + <mimicJoint>gripper_right_fingertip_3_joint</mimicJoint> + <multiplier>-1.0</multiplier> + <offset>0.0</offset> + <!-- <hasPID/> --> + </plugin> + </gazebo> + <!-- <plugin filename="libgazebo_underactuated_finger.so" name="gazebo_${name}_underactuated"> + <actuatedJoint>${name}_joint</actuatedJoint> + <virtualJoint> + <name>${name}_inner_double_joint</name> + <scale_factor>1.0</scale_factor> + </virtualJoint> --> + <!-- <virtualJoint> + <name>${name}_fingertip_1_joint</name> + <scale_factor>-1.0</scale_factor> + </virtualJoint> + <virtualJoint> + <name>${name}_fingertip_2_joint</name> + <scale_factor>-1.0</scale_factor> + </virtualJoint> + <virtualJoint> + <name>${name}_motor_single_joint</name> + <scale_factor>1.0</scale_factor> + </virtualJoint> + <virtualJoint> + <name>${name}_fingertip_3_joint</name> + <scale_factor>-1.0</scale_factor> + </virtualJoint> --> + <!-- </plugin> --> + <gazebo reference="gripper_right_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_right_inner_double_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_right_fingertip_1_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_right_fingertip_2_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_right_motor_single_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_right_fingertip_3_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <gazebo reference="gripper_right_base_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="gripper_right_motor_double_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_right_inner_double_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_right_fingertip_1_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="gripper_right_motor_single_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_right_inner_single_link"> + <material>Gazebo/Orange</material> + </gazebo> + <gazebo reference="gripper_right_fingertip_2_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="gripper_right_fingertip_3_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <transmission name="gripper_right_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="gripper_right_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="gripper_right_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + </joint> + </transmission> + <!-- virtual mimic joints --> + <!-- <xacro:gripper_virtual_transmission name="${name}_inner_double" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_1" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_2" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_inner_single" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_motor_single" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_3" reduction="1.0"/> --> <!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link --> <link name="leg_left_1_link"> <inertial> @@ -2080,3 +2783,4 @@ <color rgba="1.0 0.5 0.0 1.0"/> </material> </robot> + diff --git a/urdf/talos_reduced.urdf b/urdf/talos_reduced.urdf new file mode 120000 index 0000000000000000000000000000000000000000..ad552ccb66caf4efe8d62b09fffa1d47aa3165d9 --- /dev/null +++ b/urdf/talos_reduced.urdf @@ -0,0 +1 @@ +../robots/talos_reduced.urdf \ No newline at end of file diff --git a/urdf/talos_small.urdf b/urdf/talos_small.urdf deleted file mode 120000 index 2f83698bac463a1adc0e40e5d1cbafd6f6aff3cf..0000000000000000000000000000000000000000 --- a/urdf/talos_small.urdf +++ /dev/null @@ -1 +0,0 @@ -../robots/talos_small.urdf \ No newline at end of file