Commit 702bd668 authored by Pierre Fernbach's avatar Pierre Fernbach
Browse files

[Talos] talos_full_v2.urdf now use the collision mesh for the ankle instead of the box

parent 0589d429
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ./talos_full_v2.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">
<!--************************-->
<!-- TORSO_2 (TILT) -->
<!--************************-->
<link name="torso_2_link">
<inertial>
<mass value="16.97403"/>
<inertia ixx="0.44372633826" ixy="0.00069132133" ixz="-0.01218206353" iyy="0.2998576068" iyz="-0.00019623338" izz="0.32201554742"/>
<origin rpy="0 0 0" xyz="-0.0463563 -0.00099023 0.1452805"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/torso/torso_2.STL" scale="1 1 1"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<!--************************-->
<!-- TORSO_1 (PAN) -->
<!--************************-->
<link name="torso_1_link">
<inertial>
<mass value="2.294658"/>
<inertia ixx="0.00638508087" ixy="-7.107e-08" ixz="-3.065592e-05" iyy="0.00410256102" iyz="-1.46946e-06" izz="0.00622968815"/>
<origin rpy="0 0 0" xyz="0.00078223 3.528e-05 -0.01782457"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/torso/torso_1.STL" scale="1 1 1"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/torso/torso_1.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="torso_1_joint" type="revolute">
<parent link="base_link"/>
<child link="torso_1_link"/>
<!-- XXX AS: The kinematic chain order for the torso was reversed manually. This value does not match the CAD model. XXX -->
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0722"/>
<axis xyz="0 0 1"/>
<limit effort="200.0" lower="-1.25663706144" upper="1.25663706144" velocity="5.4"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-15.0 * deg_to_rad + torso_eps}"
soft_upper_limit="${ 45.0 * deg_to_rad - torso_eps}" /> -->
</joint>
<!--************************-->
<!-- BASE_LINK -->
<!--************************-->
<link name="base_link">
<inertial>
<mass value="15.36284"/>
<inertia ixx="0.20105075811" ixy="0.00023244734" ixz="0.0040167728" iyy="0.08411496729" iyz="-0.00087206649" izz="0.2318908414"/>
<origin rpy="0 0 0" xyz="-0.05709419 0.00153054 -0.0762521"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/torso/base_link.STL" scale="1 1 1"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/torso/base_link_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="torso_2_joint" type="revolute">
<parent link="torso_1_link"/>
<child link="torso_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 1 0"/>
<limit effort="200.0" lower="-0.226892802759" upper="0.733038285838" velocity="5.4"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-75.00000 * deg_to_rad + eps_radians}"
soft_upper_limit="${75.00000 * deg_to_rad - eps_radians}" /> -->
</joint>
<link name="imu_link">
<inertial>
<mass value="0.01"/>
<inertia ixx="1e-06" ixy="0.0" ixz="0.0" iyy="1e-06" iyz="0.0" izz="1e-06"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<joint name="imu_joint" type="fixed">
<origin rpy="3.14159265359 0 1.57079632679" xyz="0.04925 0 0.078"/>
<parent link="torso_2_link"/>
<child link="imu_link"/>
</joint>
<gazebo reference="torso_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="torso_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="base_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="torso_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="torso_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<transmission name="talos_torso_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="torso_1_motor">
<role>actuator1</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<actuator name="torso_2_motor">
<role>actuator2</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="torso_1_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="torso_2_joint">
<role>joint2</role>
<offset>0.0</offset>
<mechanicalReduction>1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="head_1_link">
<inertial>
<mass value="0.73746"/>
<inertia ixx="0.00224878584" ixy="4.69375e-06" ixz="8.55557e-05" iyy="0.00111158492" iyz="-4.132536e-05" izz="0.00205225921"/>
<origin rpy="0 0 0" xyz="-0.00157211 -0.00157919 0.02175767"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/head/head_1.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/head/head_1_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="head_1_joint" type="revolute">
<parent link="torso_2_link"/>
<child link="head_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.02000 0.00000 0.32100"/>
<axis xyz="0 1 0"/>
<limit effort="8.0" lower="-0.209439510239" upper="0.785398163397" velocity="1.0"/>
<dynamics damping="0.5" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-15.00000 * deg_to_rad + eps_radians}"
soft_upper_limit="${45.00000 * deg_to_rad - eps_radians}" /> -->
</joint>
<gazebo reference="head_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="head_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="head_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<link name="head_2_link">
<inertial>
<mass value="1.443954"/>
<inertia ixx="0.01084624339" ixy="1.050889e-05" ixz="0.00041594252" iyy="0.0109569176" iyz="2.367831e-05" izz="0.00571698895"/>
<origin rpy="0 0 0" xyz="0.01002657 5.218e-05 0.14136068"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/head/head_2.stl" scale="1 1 1"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/head/head_2_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="head_2_joint" type="revolute">
<parent link="head_1_link"/>
<child link="head_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 0 1"/>
<limit effort="4.0" lower="-1.308996939" upper="1.308996939" velocity="1.0"/>
<dynamics damping="0.5" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-75.00000 * deg_to_rad + eps_radians}"
soft_upper_limit="${75.00000 * deg_to_rad - eps_radians}" /> -->
</joint>
<gazebo reference="head_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="head_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="head_2_link">
<material>Gazebo/White</material>
</gazebo>
<!-- frames in the center of the camera -->
<joint name="rgbd_joint" type="fixed">
<origin rpy="0.0 0.0 0.0" xyz="0.066 0.0 0.1982"/>
<axis xyz="0 0 1"/>
<!-- <limit lower="0" upper="0.001" effort="100" velocity="0.01"/> -->
<parent link="head_2_link"/>
<child link="rgbd_link"/>
</joint>
<link name="rgbd_link">
<inertial>
<mass value="0.01"/>
<inertia ixx="3e-05" ixy="0.0" ixz="0.0" iyy="2e-06" iyz="0.0" izz="3e-05"/>
<origin rpy="-0.01 0.0025 0" xyz="0 0 0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/sensors/orbbec/orbbec.STL"/>
</geometry>
<material name="DarkGrey">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.01 0.0025 0"/>
<geometry>
<box size="0.04 0.185 0.03"/>
</geometry>
</collision>
</link>
<joint name="rgbd_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="rgbd_link"/>
<child link="rgbd_optical_frame"/>
</joint>
<link name="rgbd_optical_frame">
<inertial>
<mass value="0.01"/>
<inertia ixx="0" ixy="0.0" ixz="0.0" iyy="0" iyz="0.0" izz="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<!-- frames of the depth sensor -->
<joint name="rgbd_depth_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.03751 0.0"/>
<parent link="rgbd_link"/>
<child link="rgbd_depth_frame"/>
</joint>
<link name="rgbd_depth_frame"/>
<joint name="rgbd_depth_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
<parent link="rgbd_depth_frame"/>
<child link="rgbd_depth_optical_frame"/>
</joint>
<link name="rgbd_depth_optical_frame"/>
<!-- frames of the rgb sensor -->
<joint name="rgbd_rgb_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/>
<parent link="rgbd_link"/>
<child link="rgbd_rgb_frame"/>
</joint>
<link name="rgbd_rgb_frame"/>
<joint name="rgbd_rgb_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
<parent link="rgbd_rgb_frame"/>
<child link="rgbd_rgb_optical_frame"/>
</joint>
<link name="rgbd_rgb_optical_frame"/>
<gazebo reference="rgbd_link">
<!-- IR + depth -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>30.0</update_rate>
<camera>
<horizontal_fov>1.0471975512</horizontal_fov>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.6</near>
<far>8.0</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>rgb/image_raw</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<frameName>rgbd_optical_frame</frameName>
<pointCloudCutoff>0.45</pointCloudCutoff>
<rangeMax>10.0</rangeMax>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</plugin>
</sensor>
<!-- RGB High res-->
<sensor name="rgbd_high_res_frame_sensor" type="camera">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.0471975512</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin filename="libgazebo_ros_camera.so" name="rgbd_high_res_frame_controller">
<alwaysOn>true</alwaysOn>
<!-- Patch to publish at 30 Hz -->
<updateRate>45.0</updateRate>
<cameraName>rgbd/high_res</cameraName>
<imageTopicName>/rgbd/rgb/high_res/image_raw</imageTopicName>
<cameraInfoTopicName>/rgbd/rgb/high_res/camera_info</cameraInfoTopicName>
<frameName>rgbd_optical_frame</frameName>
<hackBaseline>0.0</hackBaseline>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</plugin>
</sensor>
<material>Gazebo/FlatBlack</material>
</gazebo>
<transmission name="talos_trans">
<type>transmission_interface/HalfDifferentialTransmission</type>
<actuator name="head_1_motor">
<role>actuator1</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<actuator name="head_2_motor">
<role>actuator2</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="head_1_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="head_2_joint">
<role>joint2</role>
<offset>0.0</offset>
<mechanicalReduction>2.0</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!--************************-->
<!-- SHOULDER -->
<!--************************-->
<link name="arm_left_1_link">
<inertial>
<mass value="2.714567"/>
<inertia ixx="0.01237818683" ixy="-3.625571e-05" ixz="7.14472e-05" iyy="0.004191372" iyz="-0.00023639064" izz="0.01358161109"/>
<origin rpy="0 0 0" xyz="-0.0002762 0.10060223 0.04437419"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/arm/arm_1.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/arm/arm_1_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="arm_left_1_joint" type="revolute">
<parent link="torso_2_link"/>
<child link="arm_left_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.1575 0.23200"/>
<axis xyz="0 0 1"/>
<!-- v1 TALOS has 1st arm left joint (-90,30) and right joint (-30,90) -->
<!-- v2 TALOS has 1st arm left joint (-90,50) and right joint (-50,90) -->
<limit effort="100.0" lower="-1.57079632679" upper="0.785398163397" velocity="2.7"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-90.00000 * deg_to_rad + arm_eps}"
soft_upper_limit="${30.00000 * deg_to_rad - arm_eps}" /> -->
</joint>
<link name="arm_left_2_link">
<inertial>
<mass value="2.425086"/>
<inertia ixx="0.01297822101" ixy="1.208791e-05" ixz="-0.00320370433" iyy="0.01380870278" iyz="-0.00012770059" izz="0.00478856621"/>
<origin rpy="0 0 0" xyz="0.01438831 0.00092938 -0.08684268"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/arm/arm_2.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/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="100.0" lower="0.00872664625997" upper="2.87106661953" 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>
<mass value="2.208741"/>
<inertia ixx="0.00718831493" ixy="-0.00011563551" ixz="0.00075969733" iyy="0.00693528503" iyz="0.00042134743" izz="0.00388359007"/>
<origin rpy="0 0 0" xyz="0.0136084 0.01241619 -0.2499004"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/arm/arm_3.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/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="70.0" lower="-2.42600766027" upper="2.42600766027" 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>
<mass value="0.877346"/>
<inertia ixx="0.00251207716" ixy="0.00010070062" ixz="-0.00032788214" iyy="0.00275869324" iyz="0.00040022227" izz="0.00120735959"/>
<origin rpy="0 0 0" xyz="-0.00742138 -0.0213895 -0.03312656"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/arm/arm_4.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/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="70.0" lower="-2.23402144255" upper="0.00349065850399" 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 -->
<!--************************-->
<link name="arm_left_5_link">
<inertial>
<mass value="1.877923"/>
<inertia ixx="0.00349507283" ixy="1.265489e-05" ixz="1.038286e-05" iyy="0.00436830072" iyz="-9.736042e-05" izz="0.0022826337"/>
<origin rpy="0 0 0" xyz="-6e-05 0.003262 0.079625"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package:///example-robot-data/robots/talos_data/meshes/arm/arm_5.stl" scale="1 1 1"/>
</geometry>
<material name="LightGrey"/>