diff --git a/robots/talos_left_arm.urdf b/robots/talos_left_arm.urdf new file mode 100644 index 0000000000000000000000000000000000000000..3184fc2c0a1e48221d054d8d9aa9cac78b02f9a6 --- /dev/null +++ b/robots/talos_left_arm.urdf @@ -0,0 +1,839 @@ +<?xml version="1.0" ?> +<!-- =================================================================================== --> +<!-- | This document was autogenerated by xacro from talos_full.urdf.xacro | --> +<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> +<!-- =================================================================================== --> +<!-- + + Copyright (c) 2016, PAL Robotics, S.L. + All rights reserved. + + This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. + To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to + 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"> + + + <link name="arm_left_1_link"> + <!-- TODO: Missing reflects of inertias --> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01346 0.0913 0.04812"/> + <!-- <mass value="1.52896"/> --> + <mass value="1.42896"/> + <inertia ixx="0.00555100000" ixy="-0.00073100000" ixz="0.00000800000" iyy="0.00167300000" iyz="-0.00006000000" izz="0.00582200000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_1_collision.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_data/meshes/arm/arm_1_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <link name="arm_left_2_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.02607 0.00049 -0.05209"/> + <!-- <mass value="1.77729"/> --> + <mass value="1.67729"/> + <inertia ixx="0.00708700000" ixy="-0.00001400000" ixz="0.00214200000" iyy="0.00793600000" iyz="0.00003000000" izz="0.00378800000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_2_collision.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_data/meshes/arm/arm_2_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="arm_left_2_joint" type="revolute"> + <parent link="arm_left_1_link"/> + <child link="arm_left_2_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00493 0.1365 0.04673"/> + <axis xyz="1 0 0"/> + <limit effort="22.32" lower="0.0" upper="2.87979326579" velocity="3.66"/> + <dynamics damping="1.0" friction="1.0"/> + <!-- <safety_controller k_position="20" + k_velocity="20" + soft_lower_limit="${0.00000 * deg_to_rad + arm_eps}" + soft_upper_limit="${165.00000 * deg_to_rad - arm_eps}" /> --> + </joint> + <link name="arm_left_3_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00841 0.01428 -0.22291"/> + <!-- <mass value="1.57029"/> --> + <mass value="1.47029"/> + <inertia ixx="0.00433200000" ixy="0.00015300000" ixz="-0.00049600000" iyy="0.00434000000" iyz="-0.00060900000" izz="0.00254300000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_3_collision.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_data/meshes/arm/arm_3_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="arm_left_3_joint" type="revolute"> + <parent link="arm_left_2_link"/> + <child link="arm_left_3_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/> + <axis xyz="0 0 1"/> + <limit effort="17.86" lower="-2.44346095279" upper="2.44346095279" velocity="4.58"/> + <dynamics damping="1.0" friction="1.0"/> + <!-- <safety_controller k_position="20" + k_velocity="20" + soft_lower_limit="${-140.0 * deg_to_rad + arm_eps}" + soft_upper_limit="${140.0 * deg_to_rad - arm_eps}" /> --> + </joint> + <!--************************--> + <!-- ELBOW --> + <!--************************--> + <link name="arm_left_4_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00655 -0.02107 -0.02612"/> + <!-- <mass value="1.20216"/> --> + <mass value="1.10216"/> + <inertia ixx="0.00221700000" ixy="-0.00010100000" ixz="0.00028800000" iyy="0.00241800000" iyz="-0.00039300000" izz="0.00111500000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_4_collision.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_data/meshes/arm/arm_4_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="arm_left_4_joint" type="revolute"> + <parent link="arm_left_3_link"/> + <child link="arm_left_4_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.02000 0.00000 -0.27300"/> + <axis xyz="0 1 0"/> + <limit effort="17.86" lower="-2.35619449019" upper="0.0" velocity="4.58"/> + <dynamics damping="1.0" friction="1.0"/> + <!-- <safety_controller k_position="20" + k_velocity="20" + soft_lower_limit="${-135.0 * deg_to_rad + arm_eps}" + soft_upper_limit="${0.0 * deg_to_rad - arm_eps}" /> --> + </joint> + <gazebo reference="arm_left_1_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="arm_left_2_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="arm_left_3_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="arm_left_4_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="arm_left_1_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + </gazebo> + <gazebo reference="arm_left_2_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + </gazebo> + <gazebo reference="arm_left_3_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + </gazebo> + <gazebo reference="arm_left_4_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + </gazebo> + <!--************************--> + <!-- WRIST --> + <!--************************--> + <!--************************--> + <!-- WRIST --> + <!--************************--> + <link name="arm_left_5_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00006 0.00326 0.07963"/> + <!-- <mass value="1.87792"/> --> + <mass value="1.77792"/> + <inertia ixx="0.00349500000" ixy="-0.00001300000" ixz="-0.00001000000" iyy="0.00436800000" iyz="0.00009700000" izz="0.00228300000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_5_collision.STL" scale="1 1 1"/> + </geometry> + <material name="LightGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_5_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="arm_left_5_joint" type="revolute"> + <parent link="arm_left_4_link"/> + <child link="arm_left_5_link"/> + <origin rpy="0.0 0.0 0.0" xyz="-0.02000 0.00000 -0.26430"/> + <axis xyz="0 0 1"/> + <limit effort="3" lower="-2.53072741539" upper="2.53072741539" velocity="1.95"/> + <dynamics damping="1.0" friction="1.0"/> + <!-- <safety_controller k_position="20" + k_velocity="20" + soft_lower_limit="${-145.00000 * deg_to_rad + wrist_eps}" + soft_upper_limit="${145.00000 * deg_to_rad - wrist_eps}" /> --> + </joint> + <link name="arm_left_6_link"> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.00002 -0.00197 -0.00059"/> + <!-- <mass value="0.40931"/> --> + <mass value="0.30931"/> + <inertia ixx="0.00010700000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00014100000" iyz="-0.00000000000" izz="0.00015400000"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_6_collision.STL" scale="1 1 1"/> + </geometry> + <material name="LightGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_6_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="arm_left_6_joint" type="revolute"> + <parent link="arm_left_5_link"/> + <child link="arm_left_6_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/> + <axis xyz="1 0 0"/> + <limit effort="6.6" lower="-1.3962634016" upper="1.3962634016" velocity="1.76"/> + <dynamics damping="1.0" friction="1.0"/> + <!-- <safety_controller k_position="20" + k_velocity="20" + soft_lower_limit="${-80.00000 * deg_to_rad + eps_radians}" + soft_upper_limit="${80.00000 * deg_to_rad - eps_radians}" /> --> + </joint> + <link name="arm_left_7_link"> + <!-- WRONG VALUES + <inertial> + <origin xyz="-0.00089 0.00365 -0.07824" rpy="0.00000 0.00000 0.00000"/> + <mass value="1.02604"/> + <inertia ixx="0.00151400000" ixy="0.00000600000" ixz="0.00006600000" + iyy="0.00146400000" iyz="0.00001200000" + izz="0.00090300000"/> + </inertial> + --> + <inertial> + <origin rpy="0.00000 0.00000 0.00000" xyz="0.007525 0.001378 -0.024630"/> + <mass value="0.308441"/> + <inertia ixx="0.000309" ixy="0.000002" ixz="-0.000002" iyy="0.000219" iyz="0.000012" izz="0.000176"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_data/meshes/arm/arm_7.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_data/meshes/arm/arm_7_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + <joint name="arm_left_7_joint" type="revolute"> + <parent link="arm_left_6_link"/> + <child link="arm_left_7_link"/> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> + <axis xyz="0 1 0"/> + <limit effort="6.6" lower="-0.698131700798" upper="0.698131700798" velocity="1.76"/> + <dynamics damping="1.0" friction="1.0"/> + <!-- <safety_controller k_position="20" + k_velocity="20" + soft_lower_limit="${-40.00000 * deg_to_rad + eps_radians}" + soft_upper_limit="${40.00000 * deg_to_rad - eps_radians}" /> --> + </joint> + <gazebo reference="arm_left_5_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + </gazebo> + <gazebo reference="arm_left_6_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + </gazebo> + <gazebo reference="arm_left_7_link"> + <mu1>0.9</mu1> + <mu2>0.9</mu2> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="arm_left_5_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + </gazebo> + <gazebo reference="arm_left_6_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + </gazebo> + <gazebo reference="arm_left_7_joint"> + <implicitSpringDamper>1</implicitSpringDamper> + <provideFeedback>1</provideFeedback> + </gazebo> + <!-- extensions --> + <transmission name="arm_left_5_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="arm_left_5_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="arm_left_5_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + </transmission> + <transmission name="wrist_left_trans"> + <type>transmission_interface/DifferentialTransmission</type> + <actuator name="arm_left_6_motor"> + <role>actuator1</role> + <mechanicalReduction>-1.0</mechanicalReduction> + </actuator> + <actuator name="arm_left_7_motor"> + <role>actuator2</role> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="arm_left_6_joint"> + <role>joint1</role> + <offset>0.0</offset> + <mechanicalReduction>-1.0</mechanicalReduction> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <joint name="arm_left_7_joint"> + <role>joint2</role> + <offset>0.0</offset> + <mechanicalReduction>-1.0</mechanicalReduction> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + </transmission> + <!-- extensions --> + <transmission name="arm_left_1_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="arm_left_1_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="arm_left_1_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + </transmission> + <transmission name="arm_left_2_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="arm_left_2_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="arm_left_2_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + </transmission> + <transmission name="arm_left_3_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="arm_left_3_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="arm_left_3_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + </transmission> + <transmission name="arm_left_4_trans"> + <type>transmission_interface/SimpleTransmission</type> + <actuator name="arm_left_4_motor"> + <mechanicalReduction>1.0</mechanicalReduction> + </actuator> + <joint name="arm_left_4_joint"> + <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + </transmission> + + + + + + + + + + + + + + + + <!--************************--> + <!-- ft sensor --> + <!--************************--> + <link name="wrist_left_ft_link"> + <inertial> + <mass value="0.1"/> + <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.0157" radius="0.0225"/> + </geometry> + <material name="LightGrey"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.0157" radius="0.0225"/> + </geometry> + </collision> + </link> + <joint name="wrist_left_ft_joint" type="fixed"> + <parent link="arm_left_7_link"/> + <child link="wrist_left_ft_link"/> + <origin rpy="0.0 0 -4.71238898038" xyz="0 0 -0.051"/> + </joint> + <!--***********************--> + <!-- FT TOOL --> + <!--***********************--> + <link name="wrist_left_ft_tool_link"> + <inertial> + <mass value="0.1"/> + <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> + </inertial> + <visual> + <origin rpy="0 0.0 0" xyz="0.0 0 0"/> + <geometry> + <cylinder length="0.00975" radius="0.025"/> + </geometry> + <material name="FlatBlack"/> + </visual> + <collision> + <origin rpy="0 0.0 0" xyz="0.0 0 0"/> + <geometry> + <cylinder length="0.00975" radius="0.025"/> + </geometry> + </collision> + </link> + <joint name="wrist_left_tool_joint" type="fixed"> + <parent link="wrist_left_ft_link"/> + <child link="wrist_left_ft_tool_link"/> + <origin rpy="0 0 4.71238898038" xyz="0 0 -0.012725"/> + </joint> + <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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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_data/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"/> --> + <!-- define global properties --> + <!-- <xacro:property name="M_PI" value="3.1415926535897931" /> --> + <!-- Materials for visualization --> + <material name="Blue"> + <color rgba="0.0 0.0 0.8 1.0"/> + </material> + <material name="Green"> + <color rgba="0.0 0.8 0.0 1.0"/> + </material> + <material name="Grey"> + <color rgba="0.7 0.7 0.7 1.0"/> + </material> + <material name="LightGrey"> + <color rgba="0.9 0.9 0.9 1.0"/> + </material> + <material name="DarkGrey"> + <color rgba="0.2 0.2 0.2 1.0"/> + </material> + <material name="Red"> + <color rgba="0.8 0.0 0.0 1.0"/> + </material> + <material name="White"> + <color rgba="1.0 1.0 1.0 1.0"/> + </material> + <material name="Orange"> + <color rgba="1.0 0.5 0.0 1.0"/> + </material> +</robot> +