Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • gsaurel/talos-data
  • stack-of-tasks/talos-data
2 results
Show changes
Showing
with 15124 additions and 510 deletions
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="talos">
<xacro:include filename="$(find talos_data)/urdf/leg/leg.transmission.xacro" />
<xacro:property name="deg_to_rad" value="0.01745329251994329577" />
<xacro:property name="eps_radians" value="0.008" /> <!-- 0.45deg -->
<xacro:property name="eps_meters" value="0.005" />
<xacro:property name="leg_reduction" value="1.0" />
<xacro:property name="leg_friction" value="0.0" />
<xacro:property name="leg_damping" value="0.0" />
<xacro:macro name="talos_leg" params="prefix reflect">
<!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
<link name="leg_${prefix}_1_link">
<xacro:call macro="leg_${prefix}_1_link_inertial" />
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.stl" scale="1 ${reflect*1} 1"/>
</geometry>
<material name="DarkGrey" />
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</link>
<joint name="leg_${prefix}_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_${prefix}_1_link"/>
<origin xyz="-0.02 ${reflect*0.08500} -0.27105"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 0 1" />
<limit lower="${(-55.0 + 35.0*reflect)*deg_to_rad}" upper="${(55.0 + 35.0*reflect)*deg_to_rad}" effort="100" velocity="3.87" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<link name="leg_${prefix}_1_link_passive">
<inertial>
<mass value="0.001"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
</inertial>
</link>
<joint name="leg_${prefix}_1_joint_passive" type="revolute">
<parent link="leg_${prefix}_1_link"/>
<child link="leg_${prefix}_1_link_passive"/>
<origin xyz="0.0 0.0 0.0"
rpy="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0" />
<limit lower="${(-180.0)*deg_to_rad}" upper="${(180.0)*deg_to_rad}" effort="100" velocity="3.87" />
<dynamics friction="970.0" damping="0.0"/>
</joint>
<gazebo>
<plugin filename="libSpringPlugin.so" name="spring_leg_${prefix}_1_joint_passive">
<joint_spring>leg_${prefix}_1_joint_passive</joint_spring>
<kp>970.0</kp>
<kd>0.0</kd>
</plugin>
</gazebo>
<transmission name="leg_${prefix}_1_passive_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_${prefix}_1_motor" >
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_${prefix}_1_joint_passive">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<!-- <link name="leg_${prefix}_2_link_passive"> -->
<!-- <inertial> -->
<!-- <mass value="0.001"/> -->
<!-- <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" /> -->
<!-- <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> -->
<!-- </inertial> -->
<!-- </link> -->
<!-- <joint name="leg_${prefix}_2_joint_passive" type="revolute"> -->
<!-- <parent link="leg_${prefix}_1_link_passive"/> -->
<!-- <child link="leg_${prefix}_2_link_passive"/> -->
<!-- <origin xyz="0.0 0.0 0.0" -->
<!-- rpy="0.00000 0.00000 0.00000"/> -->
<!-- <axis xyz="0 1 0" /> -->
<!-- <limit lower="${(-180.0)*deg_to_rad}" upper="${(180.0)*deg_to_rad}" effort="100" velocity="3.87" /> -->
<!-- <dynamics friction="970.0" damping="0.0"/> -->
<!-- </joint> -->
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_${prefix}_2_link">
<xacro:call macro="leg_${prefix}_2_link_inertial" />
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 ${reflect*1} 1"/>
</geometry>
<material name="DarkGrey" />
</visual>
<collision>
<origin xyz="0 0 0.0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</link>
<joint name="leg_${prefix}_2_joint" type="revolute">
<parent link="leg_${prefix}_1_link_passive"/>
<child link="leg_${prefix}_2_link"/>
<origin xyz="0.00000 0.00000 0.00000"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="-0.5236" upper="0.5236" effort="160" velocity="5.8" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_${prefix}_3_link">
<xacro:call macro="leg_${prefix}_3_link_inertial" />
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.stl" scale="1 ${reflect*1} 1"/>
</geometry>
<material name="DarkGrey" />
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</link>
<joint name="leg_${prefix}_3_joint" type="revolute">
<parent link="leg_${prefix}_2_link"/>
<child link="leg_${prefix}_3_link"/>
<origin xyz="0.00000 0.00000 0.00000"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 1 0" />
<limit lower="-2.095" upper="0.7" effort="160" velocity="5.8" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_${prefix}_4_link">
<xacro:call macro="leg_${prefix}_4_link_inertial" />
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.stl" scale="1 ${reflect*1} 1"/>
</geometry>
<material name="DarkGrey" />
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</link>
<joint name="leg_${prefix}_4_joint" type="revolute">
<parent link="leg_${prefix}_3_link"/>
<child link="leg_${prefix}_4_link"/>
<origin xyz="0.00000 0.00000 -0.38000"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 1 0" />
<limit lower="0" upper="2.618" effort="300" velocity="7" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_${prefix}_5_link">
<!-- XXX AS: this link has moving lever and inertial parameters should slightly vary depending on configuration. XXX -->
<xacro:call macro="leg_${prefix}_5_link_inertial" />
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 ${reflect*1} 1"/>
</geometry>
<material name="Grey" />
</visual>
<collision>
<origin xyz="0 0 0.0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
</link>
<joint name="leg_${prefix}_5_joint" type="revolute">
<parent link="leg_${prefix}_4_link"/>
<child link="leg_${prefix}_5_link"/>
<origin xyz="0.00000 0.00000 -0.32500"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 1 0" />
<limit lower="-1.27" upper="0.68" effort="160" velocity="5.8" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_${prefix}_6_link">
<xacro:call macro="leg_${prefix}_6_link_inertial" />
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 ${reflect*1} 1"/>
</geometry>
<material name="Grey" />
</visual>
<xacro:talos_foot_collision />
</link>
<joint name="leg_${prefix}_6_joint" type="revolute">
<parent link="leg_${prefix}_5_link"/>
<child link="leg_${prefix}_6_link"/>
<origin xyz="0.00000 0.00000 0.00000"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="-0.5236" upper="0.5236" effort="100" velocity="4.8" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<!-- from here is copy paste -->
<link name="${prefix}_sole_link">
<xacro:call macro="${prefix}_sole_link_inertial" />
</link>
<joint name="leg_${prefix}_sole_fix_joint" type="fixed">
<parent link="leg_${prefix}_6_link" />
<child link="${prefix}_sole_link" />
<origin xyz="0.00 0.00 -0.107" rpy="0 0 0" />
<axis xyz="1 0 0" />
<dynamics friction="${leg_friction}" damping="${leg_damping}"/>
</joint>
<xacro:talos_leg_simple_transmission side="${prefix}" number="1" reduction="${leg_reduction}" />
<xacro:talos_leg_simple_transmission side="${prefix}" number="2" reduction="${leg_reduction}" />
<xacro:talos_leg_simple_transmission side="${prefix}" number="3" reduction="${leg_reduction}" />
<xacro:talos_leg_simple_transmission side="${prefix}" number="4" reduction="${leg_reduction}" />
<xacro:talos_leg_simple_transmission side="${prefix}" number="5" reduction="${leg_reduction}" />
<xacro:talos_leg_simple_transmission side="${prefix}" number="6" reduction="${leg_reduction}" />
<gazebo reference="leg_${prefix}_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_${prefix}_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_${prefix}_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_${prefix}_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_${prefix}_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_${prefix}_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_${prefix}_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_${prefix}_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_${prefix}_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_${prefix}_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_${prefix}_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_${prefix}_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_${prefix}_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_${prefix}_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_${prefix}_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_${prefix}_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_${prefix}_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_${prefix}_6_link">
<material>Gazebo/White</material>
</gazebo>
</xacro:macro>
</robot>
talos_full_v2_with_lidar.urdf
\ No newline at end of file
......@@ -27,5 +27,3 @@
<xacro:property name="cal_head_mount_xtion_yaw" value="0.0" />
</robot>
<?xml version="1.0"?>
<!--
Copyright (c) 2011, 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="reemc" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="reemc_force_talosque_sensor" params="name update_rate">
<gazebo reference="${name}">
<sensor name="${name}_contact_sensor" type="contact">
<pose>0.105 0.071 0 0 0 0</pose>
<always_on>1</always_on>
<update_rate>${update_rate}</update_rate>
<contact>
<collision>${name}_collision</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="${name}">
<provideFeedback>1</provideFeedback>
</gazebo>
</xacro:macro>
</robot>
......@@ -16,10 +16,7 @@
<!-- ft sensor -->
<!--************************-->
<link name="${name}_${side}_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>
<xacro:call macro="${name}_${side}_ft_link_inertial" />
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
......@@ -45,10 +42,7 @@
<!-- FT TOOL -->
<!--***********************-->
<link name="${name}_${side}_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>
<xacro:call macro="${name}_${side}_ft_tool_link_inertial" />
<visual>
<origin xyz="0.0 0 0" rpy="0 ${0.0 * deg_to_rad} 0" />
<geometry>
......
......@@ -11,11 +11,7 @@
<xacro:macro name="talos_imu" params="name parent update_rate *origin">
<link name="${name}_link">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.000001"/>
</inertial>
<xacro:call macro="${name}_link_inertial" />
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
......
......@@ -12,7 +12,7 @@
* Publishes MONO8 format "depth" image & PointCloud
* Publishes RGB8 format color image & 2nd copy of PointCloud (for registered)
Sensor parameters are from PR2 description.
Sensor parameters are from PR2 description.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
......@@ -37,11 +37,11 @@
<pointCloudTopicName>/${camera_name}/depth/points</pointCloudTopicName>
<frameName>${frame_name}</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</controller:gazebo_ros_openni_kinect>
</sensor:camera>
</gazebo>
......@@ -66,11 +66,11 @@
<pointCloudTopicName>/${camera_name}/depth_registered/points</pointCloudTopicName>
<frameName>${frame_name}</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</controller:gazebo_ros_openni_kinect>
</sensor:camera>
</gazebo>
......
<?xml version="1.0"?>
<!--
Copyright (c) 2013, 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.
ROS Gazebo plugin for RGBD sensor (OpenNI/Kinect/ASUS)
* Publishes MONO8 format "depth" image & PointCloud
* Publishes RGB8 format color image & 2nd copy of PointCloud (for registered)
Configuration according with:
https://orbbec3d.com/product-astra-pro/
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="orbbec_astra_pro_rgbd_camera_gazebo" params="name">
<gazebo reference="${name}_link">
<!-- IR + depth -->
<sensor type="depth" name="${name}_frame_sensor">
<always_on>true</always_on>
<update_rate>30.0</update_rate>
<camera>
<horizontal_fov>${60.0 * deg_to_rad}</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 name="${name}_frame_controller" filename="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>${name}</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>${name}_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 type="camera" name="${name}_high_res_frame_sensor">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>${60.0 * deg_to_rad}</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 name="${name}_high_res_frame_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<!-- Patch to publish at 30 Hz -->
<updateRate>45.0</updateRate>
<cameraName>${name}/high_res</cameraName>
<imageTopicName>/${name}/rgb/high_res/image_raw</imageTopicName>
<cameraInfoTopicName>/${name}/rgb/high_res/camera_info</cameraInfoTopicName>
<frameName>${name}_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>
</xacro:macro>
</robot>
......@@ -24,10 +24,10 @@
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find talos_description)/urdf/sensors/xtion_pro_live.gazebo.xacro" />
<xacro:include filename="$(find talos_data)/urdf/sensors/orbbec_astra_pro.gazebo.xacro" />
<!-- Macro -->
<xacro:macro name="xtion_pro_live" params="name parent *origin *optical_origin">
<xacro:macro name="orbbec_astra_pro" params="name parent *origin *optical_origin">
<!-- frames in the center of the camera -->
<joint name="${name}_joint" type="fixed">
......@@ -39,18 +39,12 @@
</joint>
<link name="${name}_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<!-- inertia tensor computed analytically for a solid cuboid -->
<inertia ixx="0.000030" ixy="0.0" ixz="0.0"
iyy="0.000030" iyz="0.0"
izz="0.000002" />
</inertial>
<!-- inertia tensor computed analytically for a solid cuboid -->
<xacro:call macro="${name}_link_inertial" />
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/sensors/orbbec/orbbec.STL" />
<mesh filename="package://talos_data/meshes/sensors/orbbec/orbbec.STL" />
</geometry>
<material name="DarkGrey">
<color rgba="0.5 0.5 0.5 1"/>
......@@ -71,13 +65,7 @@
</joint>
<link name="${name}_optical_frame">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0"
iyy="0.0" iyz="0.0"
izz="0.0" />
</inertial>
<xacro:call macro="${name}_optical_frame_inertial" />
</link>
<!-- frames of the depth sensor -->
......@@ -115,7 +103,7 @@
<link name="${name}_rgb_optical_frame"/>
<!-- extensions -->
<xacro:xtion_pro_live_rgbd_camera_gazebo name="${name}" />
<xacro:orbbec_astra_pro_rgbd_camera_gazebo name="${name}" />
</xacro:macro>
......
......@@ -49,11 +49,11 @@
<frameName>${name}_optical_frame</frameName>
<pointCloudCutoff>0.45</pointCloudCutoff>
<rangeMax>10.0</rangeMax>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</plugin>
</sensor>
......@@ -83,11 +83,11 @@
<frameName>${name}_optical_frame</frameName>
<pointCloudCutoff>0.45</pointCloudCutoff>
<rangeMax>10.0</rangeMax>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</plugin>
</sensor>
......
......@@ -33,7 +33,7 @@
<xacro:macro name="xtion_pro_live" params="name parent *origin *calibration_origin">
<!-- base link -->
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<xacro:call macro="origin" />
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
......@@ -82,7 +82,7 @@
</link>
<!-- Xtion IR sensor frame -->
<joint name="${name}_ir_optical_frame_joint" type="fixed">
<xacro:insert_block name="calibration_origin" /> <!-- macro argument -->
<xacro:call macro="calibration_origin" /> <!-- macro argument -->
<parent link="${name}_ir_link"/>
<child link="${name}_ir_optical_frame"/>
</joint>
......@@ -117,7 +117,7 @@
</link>
<!-- Xtion RGB sensor frame -->
<joint name="${name}_rgb_optical_frame_joint" type="fixed">
<xacro:insert_block name="calibration_origin" /> <!-- macro argument -->
<xacro:call macro="calibration_origin" /> <!-- macro argument -->
<parent link="${name}_rgb_link"/>
<child link="${name}_rgb_optical_frame"/>
</joint>
......
../robots/talos_full.urdf
\ No newline at end of file
<?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">
<!--File includes-->
<!--Constant parameters-->
<!--File includes-->
<!-- Macro -->
<!--Constant parameters-->
<!--************************-->
<!-- HEAD_1 (TILT) -->
<!--************************-->
<!--************************-->
<!-- HEAD_2 (PAN) -->
<!--************************-->
<!--File includes-->
<!--File includes-->
<!--Constant parameters-->
<!--Constant parameters-->
<!--File includes-->
<!-- VIRTUAL (mimic) JOINTS -->
<!-- 0.45deg -->
<!--************************-->
<!-- TORSO_2 (TILT) -->
<!--************************-->
<link name="torso_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.04551 -0.00053 0.16386"/>
<mass value="17.55011"/>
<inertia ixx="0.37376900000" ixy="0.00063900000" ixz="0.01219600000" iyy="0.24790200000" iyz="0.00000700000" izz="0.28140400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://talos_data/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<!--************************-->
<!-- TORSO_1 (PAN) -->
<!--************************-->
<link name="torso_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00013 -0.00001 -0.01306"/>
<mass value="3.02433"/>
<inertia ixx="0.00759400000" ixy="0.00000100000" ixz="-0.00004800000" iyy="0.00429200000" iyz="-0.00000100000" izz="0.00749700000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0722"/>
<axis xyz="0 0 1"/>
<limit effort="78.0" lower="-1.308996939" upper="1.308996939" 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>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.08222 0.00838 -0.07261"/>
<mass value="13.53810"/>
<inertia ixx="0.06989000000" ixy="-0.00011700000" ixz="0.00023000000" iyy="0.03998200000" iyz="-0.00132500000" izz="0.08234500000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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="78.0" lower="-0.261799387799" upper="0.785398163397" 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"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.000001"/>
</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>
<!-- extensions -->
<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>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00120 0.00145 0.02165"/>
<mass value="0.65988"/>
<inertia ixx="0.00122100000" ixy="-0.00000400000" ixz="0.00007000000" iyy="0.00092400000" iyz="-0.00004100000" izz="0.00103300000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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.00000 0.00000 0.31600"/>
<axis xyz="0 1 0"/>
<limit effort="8.0" lower="-0.261799387799" 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>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01036 -0.00037 0.13778"/>
<mass value="1.40353"/>
<inertia ixx="0.00722500000" ixy="-0.00002500000" ixz="0.00032900000" iyy="0.00687300000" iyz="0.00004400000" izz="0.00437300000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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" 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"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- inertia tensor computed analytically for a solid cuboid -->
<inertia ixx="0.000030" ixy="0.0" ixz="0.0" iyy="0.000030" iyz="0.0" izz="0.000002"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="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"/>
<!-- extensions -->
<gazebo reference="rgbd_link">
<!-- IR + depth -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>6.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.45</near>
<far>10.0</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>6.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>ir/image_raw</imageTopicName>
<cameraInfoTopicName>ir/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>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
</plugin>
</sensor>
<!-- RGB -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>6.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.45</near>
<far>10.0</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>6.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>rgb/image_raw</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<pointCloudTopicName>rgb/points</pointCloudTopicName>
<frameName>rgbd_optical_frame</frameName>
<pointCloudCutoff>0.45</pointCloudCutoff>
<rangeMax>10.0</rangeMax>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
</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">
<!-- 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.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>
<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"/>
<limit effort="44.64" lower="-1.57079632679" upper="0.523598775598" 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>
<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.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.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.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.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.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>
<!--************************-->
<!-- SHOULDER -->
<!--************************-->
<link name="arm_right_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.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>
<joint name="arm_right_1_joint" type="revolute">
<parent link="torso_2_link"/>
<child link="arm_right_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.1575 0.23200"/>
<axis xyz="0 0 1"/>
<limit effort="44.64" lower="-0.523598775598" upper="1.57079632679" 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_right_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.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_right_2_joint" type="revolute">
<parent link="arm_right_1_link"/>
<child link="arm_right_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="-2.87979326579" upper="0.0" 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_right_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.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_right_3_joint" type="revolute">
<parent link="arm_right_2_link"/>
<child link="arm_right_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_right_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.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_right_4_joint" type="revolute">
<parent link="arm_right_3_link"/>
<child link="arm_right_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_right_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<!--************************-->
<!-- WRIST -->
<!--************************-->
<!--************************-->
<!-- WRIST -->
<!--************************-->
<link name="arm_right_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.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_right_5_joint" type="revolute">
<parent link="arm_right_4_link"/>
<child link="arm_right_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_right_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.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_right_6_joint" type="revolute">
<parent link="arm_right_5_link"/>
<child link="arm_right_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_right_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_right_7_joint" type="revolute">
<parent link="arm_right_6_link"/>
<child link="arm_right_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_right_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="arm_right_6_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="arm_right_7_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_7_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<!-- extensions -->
<transmission name="arm_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="wrist_right_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="arm_right_6_motor">
<role>actuator1</role>
<mechanicalReduction>-1.0</mechanicalReduction>
</actuator>
<actuator name="arm_right_7_motor">
<role>actuator2</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_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_right_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_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!--************************-->
<!-- ft sensor -->
<!--************************-->
<link name="wrist_right_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_right_ft_joint" type="fixed">
<parent link="arm_right_7_link"/>
<child link="wrist_right_ft_link"/>
<origin rpy="0.0 0 -1.57079632679" xyz="0 0 -0.051"/>
</joint>
<!--***********************-->
<!-- FT TOOL -->
<!--***********************-->
<link name="wrist_right_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_right_tool_joint" type="fixed">
<parent link="wrist_right_ft_link"/>
<child link="wrist_right_ft_tool_link"/>
<origin rpy="0 0 -1.57079632679" xyz="0 0 -0.012725"/>
</joint>
<!--************************-->
<!-- 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="revolute">
<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="revolute">
<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="revolute">
<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="revolute">
<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="revolute">
<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="revolute">
<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_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_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_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_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_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_right_inner_double_joint" type="revolute">
<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_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_right_fingertip_1_joint" type="revolute">
<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_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_right_fingertip_2_joint" type="revolute">
<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_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_right_motor_single_joint" type="revolute">
<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_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_right_inner_single_joint" type="revolute">
<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_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_right_fingertip_3_joint" type="revolute">
<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>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
<mass value="1.88569"/>
<inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.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/v2/hip_z_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_left_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02 0.085 -0.27105"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-0.349065850399" upper="1.57079632679" velocity="3.87"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_left_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
<mass value="2.37607"/>
<inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_2_joint" type="revolute">
<parent link="leg_left_1_link"/>
<child link="leg_left_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_left_3_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 0.06563 -0.17278"/>
<mass value="6.82734"/>
<inertia ixx="0.12390600000" ixy="-0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="0.016725" izz="0.02781200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.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/v2/hip_y_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_3_joint" type="revolute">
<parent link="leg_left_2_link"/>
<child link="leg_left_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_left_4_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 0.02331 -0.12063"/>
<mass value="3.63668"/>
<inertia ixx="0.03531500000" ixy="2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="-0.001305" izz="0.01174000000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.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/v2/knee_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_4_joint" type="revolute">
<parent link="leg_left_3_link"/>
<child link="leg_left_4_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="0" upper="2.618" velocity="7"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_left_5_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 0.04708 0.05271"/>
<mass value="1.24433"/>
<inertia ixx="0.01148700000" ixy="-0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="0.002633" izz="0.00390800000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_5_joint" type="revolute">
<parent link="leg_left_4_link"/>
<child link="leg_left_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_left_6_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
<mass value="1.59457"/>
<inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<!--
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.21 0.13 0.02"/>
</geometry>
</collision>
</link>
<joint name="leg_left_6_joint" type="revolute">
<parent link="leg_left_5_link"/>
<child link="leg_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="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- from here is copy paste -->
<link name="left_sole_link">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>
<joint name="leg_left_sole_fix_joint" type="fixed">
<parent link="leg_left_6_link"/>
<child link="left_sole_link"/>
<origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<transmission name="leg_left_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_6_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_6_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_6_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="leg_left_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_left_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_left_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_left_6_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
<link name="leg_right_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
<mass value="1.88569"/>
<inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.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/v2/hip_z_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_right_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02 -0.085 -0.27105"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-1.57079632679" upper="0.349065850399" velocity="3.87"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_right_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
<mass value="2.37607"/>
<inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_2_joint" type="revolute">
<parent link="leg_right_1_link"/>
<child link="leg_right_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_right_3_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 -0.06563 -0.17278"/>
<mass value="6.82734"/>
<inertia ixx="0.12390600000" ixy="0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="-0.016725" izz="0.02781200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.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/v2/hip_y_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_3_joint" type="revolute">
<parent link="leg_right_2_link"/>
<child link="leg_right_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_right_4_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 -0.02331 -0.12063"/>
<mass value="3.63668"/>
<inertia ixx="0.03531500000" ixy="-2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="0.001305" izz="0.01174000000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.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/v2/knee_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_4_joint" type="revolute">
<parent link="leg_right_3_link"/>
<child link="leg_right_4_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="0" upper="2.618" velocity="7"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_right_5_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 -0.04708 0.05271"/>
<mass value="1.24433"/>
<inertia ixx="0.01148700000" ixy="0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="-0.002633" izz="0.00390800000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_5_joint" type="revolute">
<parent link="leg_right_4_link"/>
<child link="leg_right_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_right_6_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
<mass value="1.59457"/>
<inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<!--
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.21 0.13 0.02"/>
</geometry>
</collision>
</link>
<joint name="leg_right_6_joint" type="revolute">
<parent link="leg_right_5_link"/>
<child link="leg_right_6_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- from here is copy paste -->
<link name="right_sole_link">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>
<joint name="leg_right_sole_fix_joint" type="fixed">
<parent link="leg_right_6_link"/>
<child link="right_sole_link"/>
<origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<transmission name="leg_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_6_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_6_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_6_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="leg_right_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_right_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_right_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_right_6_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Generic simulatalos_gazebo plugins -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<ns/>
<robotSimType>pal_hardware_gazebo/PalHardwareGazebo</robotSimType>
<robotNamespace/>
<controlPeriod>0.001</controlPeriod>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_world_odometry.so" name="gazebo_ros_odometry">
<frameName>base_link</frameName>
<topicName>floating_base_pose_simulated</topicName>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
<bodyName>base_link</bodyName>
<topicName>wrench</topicName>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<!-- this is expected to be reparented to pelvis with appropriate offset
when imu_link is reduced by fixed joint reduction -->
<!-- todo: this is working with gazebo 1.4, need to write a unit test -->
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1000.0</update_rate>
<imu>
<noise>
<type>gaussian</type>
<!-- Noise parameters from Boston Dynamics
(http://gazebosim.org/wiki/Sensor_noise):
rates (rad/s): mean=0, stddev=2e-4
accels (m/s/s): mean=0, stddev=1.7e-2
rate bias (rad/s): 5e-6 - 1e-5
accel bias (m/s/s): 1e-1
Experimentally, simulation provide rates with noise of
about 1e-3 rad/s and accels with noise of about 1e-1 m/s/s.
So we don't expect to see the noise unless number of inner iterations
are increased.
We will add bias. In this model, bias is sampled once for rates
and once for accels at startup; the sign (negative or positive)
of each bias is then switched with equal probability. Thereafter,
the biases are fixed additive offsets. We choose
bias means and stddevs to produce biases close to the provided
data. -->
<!--
<rate>
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
-->
<rate>
<mean>0.0</mean>
<stddev>0.0</stddev>
<bias_mean>0.000000</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>0.0</stddev>
<bias_mean>0.0</bias_mean>
<bias_stddev>0.000</bias_stddev>
</accel>
</noise>
</imu>
</sensor>
</gazebo>
<!-- 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>
../robots/talos_full_collision.urdf
\ No newline at end of file
......@@ -13,23 +13,49 @@
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<xacro:include filename="$(find talos_description)/urdf/torso/torso.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/head/head.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/sensors/ftsensor.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" />
<xacro:if value="$(arg enable_crane)">
<xacro:include filename="$(find talos_data)/urdf/crane/crane.urdf.xacro" />
</xacro:if>
<xacro:include filename="$(find talos_data)/urdf/torso/torso.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/head/head.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/arm/arm.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/sensors/ftsensor.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/gripper/gripper.urdf.xacro" />
<xacro:if value="$(arg enable_leg_passive)">
<xacro:include filename="$(find talos_data)/urdf/leg/leg_passive.urdf.xacro" />
</xacro:if>
<xacro:unless name="var_enable_leg_passive" value="$(arg enable_leg_passive)"/>
<xacro:unless value="${var_enable_leg_passive != 'true'}">
<xacro:include filename="$(find talos_data)/urdf/leg/leg.urdf.xacro" />
</xacro:unless> -->
<xacro:include filename="$(find talos_data)/urdf/leg/foot_collision_$(arg foot_collision).urdf.xacro" />
<xacro:include filename="$(find talos_description_inertial)/urdf/inertial.xacro" />
<xacro:talos_torso name="torso" />
<xacro:if value="$(arg enable_crane)">
<xacro:crane parent="torso_2_link"/>
</xacro:if>
<xacro:talos_head name="head" parent="torso_2_link"/>
<xacro:talos_arm name="arm" parent="torso_2_link" side="left" reflect="1" />
<xacro:talos_arm name="arm" parent="torso_2_link" side="right" reflect="-1" />
<xacro:ft_sensor name="wrist" parent="arm_right_7_link" side="right" reflect="1" />
<xacro:ft_sensor name="wrist" parent="arm_left_7_link" side="left" reflect="-1" />
<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" />
<xacro:talos_leg prefix="left" reflect="1" />
<xacro:talos_leg prefix="right" reflect="-1" />
<!-- Generic simulatalos_gazebo plugins -->
<xacro:include filename="$(find talos_description)/gazebo/gazebo.urdf.xacro" />
<!-- Generic simulator_gazebo plugins -->
<xacro:include filename="$(find talos_data)/gazebo/gazebo.urdf.xacro" />
<!-- Materials for visualization -->
<xacro:include filename="$(find talos_description)/urdf/materials.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/materials.urdf.xacro" />
</robot>
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from talos_full.urdf.xacro | -->
<!-- | This document was autogenerated by xacro from ./talos_full_v2.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--
......@@ -13,44 +13,26 @@
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">
<!--File includes-->
<!--Constant parameters-->
<!--File includes-->
<!-- Macro -->
<!--Constant parameters-->
<!--************************-->
<!-- HEAD_1 (TILT) -->
<!--************************-->
<!--************************-->
<!-- HEAD_2 (PAN) -->
<!--************************-->
<!--File includes-->
<!--File includes-->
<!--Constant parameters-->
<!--Constant parameters-->
<!--File includes-->
<!-- VIRTUAL (mimic) JOINTS -->
<!-- 0.45deg -->
<!--************************-->
<!-- TORSO_2 (TILT) -->
<!--************************-->
<link name="torso_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.04551 -0.00053 0.16386"/>
<mass value="17.55011"/>
<inertia ixx="0.37376900000" ixy="0.00063900000" ixz="0.01219600000" iyy="0.24790200000" iyz="0.00000700000" izz="0.28140400000"/>
<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://talos_description/meshes/torso/torso_2.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -59,30 +41,31 @@
<!--************************-->
<link name="torso_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00013 -0.00001 -0.01306"/>
<mass value="3.02433"/>
<inertia ixx="0.00759400000" ixy="0.00000100000" ixz="-0.00004800000" iyy="0.00429200000" iyz="-0.00000100000" izz="0.00749700000"/>
<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://talos_description/meshes/torso/torso_1.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/torso/torso_1.STL" scale="1 1 1"/>
<mesh filename="package://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="78.0" lower="-1.308996939" upper="1.308996939" velocity="5.4"/>
<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"
......@@ -94,21 +77,21 @@
<!--************************-->
<link name="base_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.08222 0.00838 -0.07261"/>
<mass value="13.53810"/>
<inertia ixx="0.06989000000" ixy="-0.00011700000" ixz="0.00023000000" iyy="0.03998200000" iyz="-0.00132500000" izz="0.08234500000"/>
<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://talos_description/meshes/torso/base_link.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/torso/base_link_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/torso/base_link_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -117,7 +100,7 @@
<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="78.0" lower="-0.261799387799" upper="0.785398163397" velocity="5.4"/>
<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"
......@@ -127,8 +110,8 @@
<link name="imu_link">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.000001"/>
<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"/>
......@@ -161,7 +144,6 @@
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<!-- extensions -->
<transmission name="talos_torso_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="torso_1_motor">
......@@ -189,30 +171,30 @@
</transmission>
<link name="head_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00120 0.00145 0.02165"/>
<mass value="0.65988"/>
<inertia ixx="0.00122100000" ixy="-0.00000400000" ixz="0.00007000000" iyy="0.00092400000" iyz="-0.00004100000" izz="0.00103300000"/>
<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://talos_description/meshes/head/head_1.stl" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/head/head_1_collision.stl" scale="1 1 1"/>
<mesh filename="package://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.00000 0.00000 0.31600"/>
<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.261799387799" upper="0.785398163397" velocity="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"
......@@ -231,21 +213,21 @@
</gazebo>
<link name="head_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01036 -0.00037 0.13778"/>
<mass value="1.40353"/>
<inertia ixx="0.00722500000" ixy="-0.00002500000" ixz="0.00032900000" iyy="0.00687300000" iyz="0.00004400000" izz="0.00437300000"/>
<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://talos_description/meshes/head/head_2.stl" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/head/head_2_collision.stl" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/head/head_2_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -273,7 +255,7 @@
</gazebo>
<!-- frames in the center of the camera -->
<joint name="rgbd_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.066 0.0 0.1982"/>
<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"/>
......@@ -282,14 +264,13 @@
<link name="rgbd_link">
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- inertia tensor computed analytically for a solid cuboid -->
<inertia ixx="0.000030" ixy="0.0" ixz="0.0" iyy="0.000030" iyz="0.0" izz="0.000002"/>
<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://talos_description/meshes/sensors/orbbec/orbbec.STL"/>
<mesh filename="package://talos_data/meshes/sensors/orbbec/orbbec.STL"/>
</geometry>
<material name="DarkGrey">
<color rgba="0.5 0.5 0.5 1"/>
......@@ -310,8 +291,8 @@
<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"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>
<!-- frames of the depth sensor -->
......@@ -340,74 +321,79 @@
<child link="rgbd_rgb_optical_frame"/>
</joint>
<link name="rgbd_rgb_optical_frame"/>
<!-- extensions -->
<gazebo reference="rgbd_link">
<!-- IR + depth -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>6.0</update_rate>
<update_rate>30.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<horizontal_fov>1.0471975512</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>320</width>
<height>240</height>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.45</near>
<far>10.0</far>
<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>6.0</updateRate>
<updateRate>30.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>ir/image_raw</imageTopicName>
<cameraInfoTopicName>ir/camera_info</cameraInfoTopicName>
<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>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</plugin>
</sensor>
<!-- RGB -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>6.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<!-- 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>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.45</near>
<far>10.0</far>
<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_openni_kinect.so" name="rgbd_frame_controller">
<plugin filename="libgazebo_ros_camera.so" name="rgbd_high_res_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>6.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>rgb/image_raw</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<pointCloudTopicName>rgb/points</pointCloudTopicName>
<!-- 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>
<pointCloudCutoff>0.45</pointCloudCutoff>
<rangeMax>10.0</rangeMax>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
<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>
......@@ -441,24 +427,22 @@
<!-- SHOULDER -->
<!--************************-->
<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"/>
<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://talos_description/meshes/arm/arm_1.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_1_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_1_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -467,7 +451,9 @@
<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"/>
<limit effort="44.64" lower="-1.57079632679" upper="0.523598775598" velocity="2.7"/>
<!-- 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"
......@@ -476,22 +462,21 @@
</joint>
<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"/>
<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://talos_description/meshes/arm/arm_2.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_2_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_2_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -500,7 +485,7 @@
<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"/>
<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"
......@@ -509,22 +494,21 @@
</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"/>
<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://talos_description/meshes/arm/arm_3.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_3_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_3_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -533,7 +517,7 @@
<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"/>
<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"
......@@ -545,22 +529,21 @@
<!--************************-->
<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"/>
<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://talos_description/meshes/arm/arm_4.STL" scale="1 1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_4_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_4_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -569,7 +552,7 @@
<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"/>
<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"
......@@ -611,27 +594,23 @@
<!--************************-->
<!-- 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"/>
<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://talos_description/meshes/arm/arm_5.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_5.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_description/meshes/arm/arm_5_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_5_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -640,7 +619,7 @@
<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"/>
<limit effort="20.0" lower="-2.51327412287" upper="2.51327412287" velocity="1.95"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -649,22 +628,21 @@
</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"/>
<mass value="0.40931"/>
<inertia ixx="0.00010700023" ixy="-8.899e-08" ixz="-4.392e-08" iyy="0.00014101316" iyz="4.1702e-07" izz="0.00015398658"/>
<origin rpy="0 0 0" xyz="2.1e-05 -0.001965 -0.000591"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/arm/arm_6.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_6.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_description/meshes/arm/arm_6_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_6_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -673,7 +651,7 @@
<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"/>
<limit effort="8.0" lower="-1.37008346282" upper="1.37008346282" velocity="1.76"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -681,31 +659,22 @@
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"/>
<inertia ixx="0.00030894317" ixy="-1.58687e-06" ixz="1.73418e-06" iyy="0.00021886181" iyz="-1.221167e-05" izz="0.00017519492"/>
<origin rpy="0 0 0" xyz="0.007525 0.001378 -0.02463"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/arm/arm_7.STL" scale="1 1 1"/>
<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_description/meshes/arm/arm_7_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_7_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -714,7 +683,7 @@
<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"/>
<limit effort="8.0" lower="-0.680678408278" upper="0.680678408278" velocity="1.76"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -744,13 +713,13 @@
<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">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -780,13 +749,13 @@
<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">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -797,6 +766,7 @@
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_left_2_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -807,6 +777,7 @@
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_left_3_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -817,6 +788,7 @@
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_left_4_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -825,24 +797,22 @@
<!-- SHOULDER -->
<!--************************-->
<link name="arm_right_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"/>
<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://talos_description/meshes/arm/arm_1.STL" scale="1 -1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_1_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_1_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -851,7 +821,9 @@
<child link="arm_right_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.1575 0.23200"/>
<axis xyz="0 0 1"/>
<limit effort="44.64" lower="-0.523598775598" upper="1.57079632679" velocity="2.7"/>
<!-- 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="-0.785398163397" upper="1.57079632679" velocity="2.7"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -860,22 +832,21 @@
</joint>
<link name="arm_right_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"/>
<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://talos_description/meshes/arm/arm_2.STL" scale="1 -1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_2_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_2_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -884,7 +855,7 @@
<child link="arm_right_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="-2.87979326579" upper="0.0" velocity="3.66"/>
<limit effort="100.0" lower="-2.87106661953" upper="-0.00872664625997" velocity="3.66"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -893,22 +864,21 @@
</joint>
<link name="arm_right_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"/>
<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://talos_description/meshes/arm/arm_3.STL" scale="1 -1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_3_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_3_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -917,7 +887,7 @@
<child link="arm_right_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"/>
<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"
......@@ -929,22 +899,21 @@
<!--************************-->
<link name="arm_right_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"/>
<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://talos_description/meshes/arm/arm_4.STL" scale="1 -1 1"/>
<mesh filename="package://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://talos_description/meshes/arm/arm_4_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_4_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -953,7 +922,7 @@
<child link="arm_right_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"/>
<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"
......@@ -995,27 +964,23 @@
<!--************************-->
<!-- WRIST -->
<!--************************-->
<!--************************-->
<!-- WRIST -->
<!--************************-->
<link name="arm_right_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"/>
<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://talos_description/meshes/arm/arm_5.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_5.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_description/meshes/arm/arm_5_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_5_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -1024,7 +989,7 @@
<child link="arm_right_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"/>
<limit effort="20.0" lower="-2.51327412287" upper="2.51327412287" velocity="1.95"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -1033,22 +998,21 @@
</joint>
<link name="arm_right_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"/>
<mass value="0.40931"/>
<inertia ixx="0.00010700023" ixy="8.899e-08" ixz="-4.392e-08" iyy="0.00014101316" iyz="-4.1702e-07" izz="0.00015398658"/>
<origin rpy="0 0 0" xyz="2.1e-05 0.001965 -0.000591"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/arm/arm_6.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_6.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_description/meshes/arm/arm_6_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_6_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -1057,7 +1021,7 @@
<child link="arm_right_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"/>
<limit effort="8.0" lower="-1.37008346282" upper="1.37008346282" velocity="1.76"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -1065,31 +1029,22 @@
soft_upper_limit="${80.00000 * deg_to_rad - eps_radians}" /> -->
</joint>
<link name="arm_right_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"/>
<inertia ixx="0.00030894317" ixy="1.58687e-06" ixz="1.73418e-06" iyy="0.00021886181" iyz="1.221167e-05" izz="0.00017519492"/>
<origin rpy="0 0 0" xyz="0.007525 -0.001378 -0.02463"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/arm/arm_7.STL" scale="1 -1 1"/>
<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_description/meshes/arm/arm_7_collision.STL" scale="1 -1 1"/>
<mesh filename="package://talos_data/meshes/arm/arm_7_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -1098,7 +1053,7 @@
<child link="arm_right_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"/>
<limit effort="8.0" lower="-0.680678408278" upper="0.680678408278" velocity="1.76"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
......@@ -1128,13 +1083,13 @@
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<!-- extensions -->
<transmission name="arm_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_5_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -1159,18 +1114,18 @@
<joint name="arm_right_7_joint">
<role>joint2</role>
<offset>0.0</offset>
<mechanicalReduction>1.0</mechanicalReduction>
<mechanicalReduction>-1.0</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- extensions -->
<transmission name="arm_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_1_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -1181,6 +1136,7 @@
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_2_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -1191,6 +1147,7 @@
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_3_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -1201,6 +1158,7 @@
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_4_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
......@@ -1210,8 +1168,9 @@
<!--************************-->
<link name="wrist_right_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"/>
<mass value="0.095"/>
<inertia ixx="1.108502e-05" ixy="9.9077e-07" ixz="-2.3811e-07" iyy="1.092725e-05" iyz="2.3137e-07" izz="1.898772e-05"/>
<origin rpy="0 0 0" xyz="-0.001001 0.000995 -0.008108"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
......@@ -1237,8 +1196,9 @@
<!--***********************-->
<link name="wrist_right_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"/>
<mass value="0.001"/>
<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>
<visual>
<origin rpy="0 0.0 0" xyz="0.0 0 0"/>
......@@ -1264,8 +1224,9 @@
<!--************************-->
<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"/>
<mass value="0.095"/>
<inertia ixx="1.108502e-05" ixy="9.9077e-07" ixz="-2.3811e-07" iyy="1.092725e-05" iyz="2.3137e-07" izz="1.898772e-05"/>
<origin rpy="0 0 0" xyz="-0.001001 0.000995 -0.008108"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
......@@ -1291,8 +1252,9 @@
<!--***********************-->
<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"/>
<mass value="0.001"/>
<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>
<visual>
<origin rpy="0 0.0 0" xyz="0.0 0 0"/>
......@@ -1315,21 +1277,21 @@
</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"/>
<mass value="0.637534"/>
<inertia ixx="0.0005849692" ixy="4.37159e-06" ixz="-1.2589e-05" iyy="0.00067076439" iyz="2.824361e-05" izz="0.00085526645"/>
<origin rpy="0 0 0" xyz="2.8e-05 0.005394 -0.023654"/>
</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"/>
<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_description/meshes/gripper/base_link_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/base_link_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1341,23 +1303,21 @@
</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"/>
<mass value="0.134356"/>
<inertia ixx="0.00013479919" ixy="6.184429e-05" ixz="-3.0798e-05" iyy="0.00019602207" iyz="4.707722e-05" izz="0.00024217879"/>
<origin rpy="0 0 0" xyz="0.019654 0.018572 -0.011998"/>
</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"/>
<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_description/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1366,26 +1326,26 @@
<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"/>
<limit effort="1.0" lower="-0.959931088597" 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"/>
<mass value="0.087986"/>
<inertia ixx="7.410642e-05" ixy="-7.4773e-07" ixz="1.01536e-06" iyy="0.0001279418" iyz="2.504083e-05" izz="0.00010495175"/>
<origin rpy="0 0 0" xyz="-0.013283 0.036852 -0.023153"/>
</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"/>
<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_description/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1399,21 +1359,21 @@
</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"/>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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"/>
<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_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1427,21 +1387,21 @@
</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"/>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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"/>
<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_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1455,21 +1415,21 @@
</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"/>
<mass value="0.107923"/>
<inertia ixx="8.973662e-05" ixy="-4.082027e-05" ixz="-1.927099e-05" iyy="0.00011957255" iyz="-2.873284e-05" izz="0.00015469079"/>
<origin rpy="0 0 0" xyz="0.025237 -0.011231 -0.008158"/>
</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"/>
<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_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1483,21 +1443,21 @@
</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"/>
<mass value="0.047177"/>
<inertia ixx="4.199818e-05" ixy="1.3418e-07" ixz="1.9358e-07" iyy="3.231338e-05" iyz="-1.509136e-05" izz="2.168842e-05"/>
<origin rpy="0 0 0" xyz="0 -0.034565 -0.021412"/>
</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"/>
<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_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1511,21 +1471,21 @@
</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"/>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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"/>
<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_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1543,42 +1503,42 @@
<mimicJoint>gripper_left_inner_double_joint</mimicJoint>
<multiplier>1.0</multiplier>
<offset>0.0</offset>
<!-- <hasPID/> -->
<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/> -->
<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/> -->
<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/> -->
<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/> -->
<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/> -->
<hasPID/>
</plugin>
</gazebo>
<!-- <plugin filename="libgazebo_underactuated_finger.so" name="gazebo_${name}_underactuated">
......@@ -1670,21 +1630,21 @@
<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"/>
<mass value="0.637534"/>
<inertia ixx="0.0005849692" ixy="4.37159e-06" ixz="-1.2589e-05" iyy="0.00067076439" iyz="2.824361e-05" izz="0.00085526645"/>
<origin rpy="0 0 0" xyz="2.8e-05 0.005394 -0.023654"/>
</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"/>
<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_description/meshes/gripper/base_link_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/base_link_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1696,23 +1656,21 @@
</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"/>
<mass value="0.134356"/>
<inertia ixx="0.00013479919" ixy="6.184429e-05" ixz="-3.0798e-05" iyy="0.00019602207" iyz="4.707722e-05" izz="0.00024217879"/>
<origin rpy="0 0 0" xyz="0.019654 0.018572 -0.011998"/>
</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"/>
<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_description/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1721,26 +1679,26 @@
<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"/>
<limit effort="1.0" lower="-0.959931088597" 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"/>
<mass value="0.087986"/>
<inertia ixx="7.410642e-05" ixy="-7.4773e-07" ixz="1.01536e-06" iyy="0.0001279418" iyz="2.504083e-05" izz="0.00010495175"/>
<origin rpy="0 0 0" xyz="-0.013283 0.036852 -0.023153"/>
</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"/>
<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_description/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1754,21 +1712,21 @@
</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"/>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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"/>
<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_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1782,21 +1740,21 @@
</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"/>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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"/>
<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_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1810,21 +1768,21 @@
</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"/>
<mass value="0.107923"/>
<inertia ixx="8.973662e-05" ixy="-4.082027e-05" ixz="-1.927099e-05" iyy="0.00011957255" iyz="-2.873284e-05" izz="0.00015469079"/>
<origin rpy="0 0 0" xyz="0.025237 -0.011231 -0.008158"/>
</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"/>
<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_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1838,21 +1796,21 @@
</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"/>
<mass value="0.047177"/>
<inertia ixx="4.199818e-05" ixy="1.3418e-07" ixz="1.9358e-07" iyy="3.231338e-05" iyz="-1.509136e-05" izz="2.168842e-05"/>
<origin rpy="0 0 0" xyz="0 -0.034565 -0.021412"/>
</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"/>
<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_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1866,21 +1824,21 @@
</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"/>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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"/>
<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_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
<mesh filename="package://talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -1898,42 +1856,42 @@
<mimicJoint>gripper_right_inner_double_joint</mimicJoint>
<multiplier>1.0</multiplier>
<offset>0.0</offset>
<!-- <hasPID/> -->
<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/> -->
<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/> -->
<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/> -->
<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/> -->
<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/> -->
<hasPID/>
</plugin>
</gazebo>
<!-- <plugin filename="libgazebo_underactuated_finger.so" name="gazebo_${name}_underactuated">
......@@ -2026,21 +1984,21 @@
<!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
<link name="leg_left_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
<mass value="1.88569"/>
<inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
<mass value="1.845591"/>
<inertia ixx="0.00541533521" ixy="-0.00015428714" ixz="0.00131612622" iyy="0.00848624936" iyz="-1.906103e-05" izz="0.00474512541"/>
<origin rpy="0 0 0" xyz="0.02247868 0.00106736 0.03130665"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_z_lo_res.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.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/v2/hip_z_collision.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_z_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -2055,21 +2013,21 @@
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_left_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
<mass value="2.37607"/>
<inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
<mass value="1.490952"/>
<inertia ixx="0.00497152259" ixy="-0.0001311358" ixz="-4.86648e-06" iyy="0.00190550993" iyz="4.585381e-05" izz="0.00474289754"/>
<origin rpy="0 0 0" xyz="-0.00704703 0.02592659 0.00273385"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_x_lo_res.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_x_collision.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -2084,21 +2042,21 @@
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_left_3_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 0.06563 -0.17278"/>
<mass value="6.82734"/>
<inertia ixx="0.12390600000" ixy="-0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="0.016725" izz="0.02781200000"/>
<mass value="6.239871"/>
<inertia ixx="0.15337403915" ixy="0.00068913396" ixz="0.00168034366" iyy="0.13648139346" iyz="-0.02187635445" izz="0.03001594885"/>
<origin rpy="0 0 0" xyz="0.0058523 0.0636967 -0.18339564"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_y_lo_res.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.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/v2/hip_y_collision.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_y_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -2113,21 +2071,21 @@
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_left_4_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 0.02331 -0.12063"/>
<mass value="3.63668"/>
<inertia ixx="0.03531500000" ixy="2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="-0.001305" izz="0.01174000000"/>
<mass value="3.759951"/>
<inertia ixx="0.04287677484" ixy="0.00043705397" ixz="0.00078292368" iyy="0.03598906971" iyz="0.00037717694" izz="0.01364791564"/>
<origin rpy="0 0 0" xyz="0.01317717 0.02917508 -0.11594602"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/knee_lo_res.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.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/v2/knee_collision.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/knee_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -2142,21 +2100,21 @@
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_left_5_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 0.04708 0.05271"/>
<mass value="1.24433"/>
<inertia ixx="0.01148700000" ixy="-0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="0.002633" izz="0.00390800000"/>
<mass value="1.29096"/>
<inertia ixx="0.01143430819" ixy="0.00096978273" ixz="0.00039976581" iyy="0.00888974312" iyz="-0.00277808667" izz="0.00506373875"/>
<origin rpy="0 0 0" xyz="-0.01400838 0.04180064 0.03820186"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_Y_lo_res.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_Y_collision.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
......@@ -2165,32 +2123,23 @@
<child link="leg_left_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
<limit effort="160" lower="-1.27" upper="0.68" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_left_6_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
<mass value="1.59457"/>
<inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
<mass value="1.597773"/>
<inertia ixx="0.00439027267" ixy="-6.743674e-05" ixz="0.00113816363" iyy="0.00743063029" iyz="3.943143e-05" izz="0.00550906699"/>
<origin rpy="0 0 0" xyz="-0.02034668 -0.00051514 -0.05987428"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_X_lo_res.stl" scale="1 1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<!--
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
......@@ -2209,9 +2158,9 @@
<!-- from here is copy paste -->
<link name="left_sole_link">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<joint name="leg_left_sole_fix_joint" type="fixed">
......@@ -2352,21 +2301,21 @@
<!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
<link name="leg_right_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
<mass value="1.88569"/>
<inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
<mass value="1.845591"/>
<inertia ixx="0.00541533521" ixy="0.00015428714" ixz="0.00131612622" iyy="0.00848624936" iyz="1.906103e-05" izz="0.00474512541"/>
<origin rpy="0 0 0" xyz="0.02247868 -0.00106736 0.03130665"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_z_lo_res.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.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/v2/hip_z_collision.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_z_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -2381,21 +2330,21 @@
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_right_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
<mass value="2.37607"/>
<inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
<mass value="1.490952"/>
<inertia ixx="0.00497152259" ixy="0.0001311358" ixz="-4.86648e-06" iyy="0.00190550993" iyz="-4.585381e-05" izz="0.00474289754"/>
<origin rpy="0 0 0" xyz="-0.00704703 -0.02592659 0.00273385"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_x_lo_res.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_x_collision.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -2410,21 +2359,21 @@
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_right_3_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 -0.06563 -0.17278"/>
<mass value="6.82734"/>
<inertia ixx="0.12390600000" ixy="0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="-0.016725" izz="0.02781200000"/>
<mass value="6.239871"/>
<inertia ixx="0.15337403915" ixy="-0.00068913396" ixz="0.00168034366" iyy="0.13648139346" iyz="0.02187635445" izz="0.03001594885"/>
<origin rpy="0 0 0" xyz="0.0058523 -0.0636967 -0.18339564"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/hip_y_lo_res.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.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/v2/hip_y_collision.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/hip_y_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -2439,21 +2388,21 @@
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_right_4_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 -0.02331 -0.12063"/>
<mass value="3.63668"/>
<inertia ixx="0.03531500000" ixy="-2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="0.001305" izz="0.01174000000"/>
<mass value="3.759951"/>
<inertia ixx="0.04287677484" ixy="-0.00043705397" ixz="0.00078292368" iyy="0.03598906971" iyz="-0.00037717694" izz="0.01364791564"/>
<origin rpy="0 0 0" xyz="0.01317717 -0.02917508 -0.11594602"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/knee_lo_res.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.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/v2/knee_collision.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/knee_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -2468,21 +2417,21 @@
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_right_5_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 -0.04708 0.05271"/>
<mass value="1.24433"/>
<inertia ixx="0.01148700000" ixy="0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="-0.002633" izz="0.00390800000"/>
<mass value="1.29096"/>
<inertia ixx="0.01143430819" ixy="-0.00096978273" ixz="0.00039976581" iyy="0.00888974312" iyz="0.00277808667" izz="0.00506373875"/>
<origin rpy="0 0 0" xyz="-0.01400838 -0.04180064 0.03820186"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_Y_lo_res.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_Y_collision.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
......@@ -2491,32 +2440,23 @@
<child link="leg_right_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
<limit effort="160" lower="-1.27" upper="0.68" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_right_6_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
<mass value="1.59457"/>
<inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
<mass value="1.597773"/>
<inertia ixx="0.00439027267" ixy="6.743674e-05" ixz="0.00113816363" iyy="0.00743063029" iyz="-3.943143e-05" izz="0.00550906699"/>
<origin rpy="0 0 0" xyz="-0.02034668 0.00051514 -0.05987428"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_X_lo_res.stl" scale="1 -1.0 1"/>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<!--
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
</geometry>
</collision>
-->
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
......@@ -2535,9 +2475,9 @@
<!-- from here is copy paste -->
<link name="right_sole_link">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<joint name="leg_right_sole_fix_joint" type="fixed">
......@@ -2675,7 +2615,6 @@
<gazebo reference="leg_right_6_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Generic simulatalos_gazebo plugins -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<ns/>
......@@ -2755,7 +2694,6 @@
</gazebo>
<!-- 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>
......
......@@ -13,13 +13,6 @@
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<xacro:include filename="$(find talos_description)/urdf/torso/torso.urdf.xacro" />
<xacro:talos_torso name="torso" />
<!-- Generic simulatalos_gazebo plugins -->
<xacro:include filename="$(find talos_description)/gazebo/gazebo.urdf.xacro" />
<!-- Materials for visualization -->
<xacro:include filename="$(find talos_description)/urdf/materials.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/arm/arm_specifics_v2.urdf.xacro" />
<xacro:include filename="$(find talos_data)/urdf/talos_full_common.urdf.xacro" />
</robot>
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | 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">
<!--************************-->
<!-- 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://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://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://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://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://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://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://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://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://talos_data/meshes/head/head_2_lidar.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/head/head_2_lidar_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>
<material name="head_d435_camera_aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<!-- camera body, with origin at bottom screw mount -->
<joint name="head_d435_camera_joint" type="fixed">
<origin rpy="0.0 0.785398163397 0.0" xyz="0.074 0.0 0.135"/>
<parent link="head_2_link"/>
<child link="head_d435_camera_bottom_screw_frame"/>
</joint>
<link name="head_d435_camera_bottom_screw_frame"/>
<joint name="head_d435_camera_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0175 0.0125"/>
<parent link="head_d435_camera_bottom_screw_frame"/>
<child link="head_d435_camera_link"/>
</joint>
<link name="head_d435_camera_link">
<visual>
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.0149 -0.0175 0"/>
<geometry>
<box size="0.090 0.025 0.02505"/>
<!--mesh filename="package://realsense2_description/meshes/d435.dae"/>-->
<!--<mesh filename="package://realsense2_description/meshes/d435/d435.dae" />-->
</geometry>
<material name="head_d435_camera_aluminum"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 -0.0175 0"/>
<geometry>
<box size="0.02505 0.09 0.025"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.564"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257"/>
</inertial>
</link>
<!-- camera depth joints and links -->
<joint name="head_d435_camera_depth_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="head_d435_camera_link"/>
<child link="head_d435_camera_depth_frame"/>
</joint>
<link name="head_d435_camera_depth_frame"/>
<joint name="head_d435_camera_depth_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_d435_camera_depth_frame"/>
<child link="head_d435_camera_depth_optical_frame"/>
</joint>
<link name="head_d435_camera_depth_optical_frame"/>
<!-- camera left IR joints and links -->
<joint name="head_d435_camera_left_ir_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0 0"/>
<parent link="head_d435_camera_depth_frame"/>
<child link="head_d435_camera_left_ir_frame"/>
</joint>
<link name="head_d435_camera_left_ir_frame"/>
<joint name="head_d435_camera_left_ir_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_d435_camera_left_ir_frame"/>
<child link="head_d435_camera_left_ir_optical_frame"/>
</joint>
<link name="head_d435_camera_left_ir_optical_frame"/>
<!-- camera right IR joints and links -->
<joint name="head_d435_camera_right_ir_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.05 0"/>
<parent link="head_d435_camera_depth_frame"/>
<child link="head_d435_camera_right_ir_frame"/>
</joint>
<link name="head_d435_camera_right_ir_frame"/>
<joint name="head_d435_camera_right_ir_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_d435_camera_right_ir_frame"/>
<child link="head_d435_camera_right_ir_optical_frame"/>
</joint>
<link name="head_d435_camera_right_ir_optical_frame"/>
<!-- camera color joints and links -->
<joint name="head_d435_camera_color_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.015 0"/>
<parent link="head_d435_camera_depth_frame"/>
<child link="head_d435_camera_color_frame"/>
</joint>
<link name="head_d435_camera_color_frame"/>
<joint name="head_d435_camera_color_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_d435_camera_color_frame"/>
<child link="head_d435_camera_color_optical_frame"/>
</joint>
<link name="head_d435_camera_color_optical_frame"/>
<gazebo reference="head_d435_camera_link">
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<!--<mu>1</mu>-->
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<!--<slip1>0</slip1>
<slip2>0</slip2>-->
<kp>1e+13</kp>
<kd>1</kd>
<!--<max_vel>0.01</max_vel>
<min_depth>0</min_depth>-->
<sensor name="head_d435_cameracolor" type="camera">
<camera name="head_d435_camera">
<horizontal_fov>1.21125850088</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
</sensor>
<sensor name="head_d435_cameraired1" type="camera">
<camera name="head_d435_camera">
<horizontal_fov>1.4870205227</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.05</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="head_d435_cameraired2" type="camera">
<camera name="head_d435_camera">
<horizontal_fov>1.4870205227</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.05</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
<sensor name="head_d435_cameradepth" type="depth">
<camera name="head_d435_camera">
<horizontal_fov>1.4870205227</horizontal_fov>
<image>
<width>1280</width>
<height>720</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.100</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>90</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin filename="librealsense_gazebo_plugin.so" name="head_d435_camera">
<prefix>head_d435_camera</prefix>
<depthUpdateRate>30.0</depthUpdateRate>
<colorUpdateRate>30.0</colorUpdateRate>
<infraredUpdateRate>30.0</infraredUpdateRate>
<depthTopicName>depth/image_raw</depthTopicName>
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
<colorTopicName>color/image_raw</colorTopicName>
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
<infrared1TopicName>infra1/image_raw</infrared1TopicName>
<infrared1CameraInfoTopicName>infra1/camera_info</infrared1CameraInfoTopicName>
<infrared2TopicName>infra2/image_raw</infrared2TopicName>
<infrared2CameraInfoTopicName>infra2/camera_info</infrared2CameraInfoTopicName>
<colorOpticalframeName>head_d435_camera_color_optical_frame</colorOpticalframeName>
<depthOpticalframeName>head_d435_camera_depth_optical_frame</depthOpticalframeName>
<infrared1OpticalframeName>head_d435_camera_left_ir_optical_frame</infrared1OpticalframeName>
<infrared2OpticalframeName>head_d435_camera_right_ir_optical_frame</infrared2OpticalframeName>
<rangeMinDepth>0.2</rangeMinDepth>
<rangeMaxDepth>10.0</rangeMaxDepth>
<pointCloud>True</pointCloud>
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
<pointCloudCutoff>0.25</pointCloudCutoff>
<pointCloudCutoffMax>9.0</pointCloudCutoffMax>
</plugin>
</gazebo>
<material name="head_t265_camera_aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<!-- camera body, with origin at camera_link -->
<joint name="head_t265_camera_pose_frame_joint" type="fixed">
<origin rpy="0.0 0.0872664625997 0.0" xyz="0.109 0.0 0.196"/>
<parent link="head_2_link"/>
<child link="head_t265_camera_pose_frame"/>
</joint>
<link name="head_t265_camera_pose_frame"/>
<joint name="head_t265_camera_pose_joint" type="fixed">
<origin rpy="1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_t265_camera_pose_frame"/>
<child link="head_t265_camera_link"/>
</joint>
<link name="head_t265_camera_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.090 0.025 0.02505"/>
</geometry>
<material name="head_t265_camera_aluminum"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.090 0.025 0.02505"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.068024"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.0000039782" ixy="0.0" ixz="0.000000034641" iyy="0.000065045" iyz="0.0" izz="0.000067499"/>
</inertial>
</link>
<joint name="head_t265_camera_fisheye1_rgb_joint" type="fixed">
<origin rpy="0 1.57079632679 1.57079632679" xyz="-0.0411 0.0 0.0"/>
<parent link="head_t265_camera_link"/>
<child link="head_t265_camera_fisheye1_rgb_frame"/>
</joint>
<link name="head_t265_camera_fisheye1_rgb_frame"/>
<joint name="head_t265_camera_fisheye2_rgb_joint" type="fixed">
<origin rpy="0 1.57079632679 1.57079632679" xyz="0.0229 0.0 0.0"/>
<parent link="head_t265_camera_link"/>
<child link="head_t265_camera_fisheye2_rgb_frame"/>
</joint>
<link name="head_t265_camera_fisheye2_rgb_frame"/>
<joint name="head_t265_camera_fisheye1_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_t265_camera_fisheye1_rgb_frame"/>
<child link="head_t265_camera_fisheye1_optical_frame"/>
</joint>
<link name="head_t265_camera_fisheye1_optical_frame"/>
<joint name="head_t265_camera_fisheye2_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
<parent link="head_t265_camera_fisheye2_rgb_frame"/>
<child link="head_t265_camera_fisheye2_optical_frame"/>
</joint>
<link name="head_t265_camera_fisheye2_optical_frame"/>
<!-- camera depth joints and links -->
<joint name="head_t265_camera_gyro_optical_joint" type="fixed">
<origin rpy="0 3.14159265359 0" xyz="-0.0311 0 0.00655"/>
<parent link="head_t265_camera_link"/>
<child link="head_t265_camera_gyro_optical_frame"/>
</joint>
<link name="head_t265_camera_gyro_optical_frame"/>
<joint name="head_t265_camera_accel_optical_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="head_t265_camera_gyro_optical_frame"/>
<child link="head_t265_camera_accel_optical_frame"/>
</joint>
<link name="head_t265_camera_accel_optical_frame"/>
<!-- Load parameters to model's main link-->
<gazebo reference="head_t265_camera_fisheye1_rgb_frame">
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<!--<mu>1</mu>-->
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<!--<slip1>0</slip1>
<slip2>0</slip2>-->
<kp>1e+13</kp>
<kd>1</kd>
<!--<max_vel>0.01</max_vel>
<min_depth>0</min_depth>-->
<sensor name="head_t265_camerafisheye1" type="wideanglecamera">
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1.95</horizontal_fov>
<image>
<width>848</width>
<height>800</height>
</image>
<clip>
<near>0.2</near>
<far>100</far>
</clip>
<lens>
<!-- type element is mandatory -->
<type>orthographic</type>
<!-- if it is set to `true` your horizontal FOV will remain as defined -->
<!-- othervise it depends on lens type and custom function, if there is one -->
<scale_to_hfov>true</scale_to_hfov>
<!-- clip everything that is outside of this angle -->
<!-- eye balled value for these cameras-->
<cutoff_angle>2.20</cutoff_angle>
<!-- resolution of the cubemap texture, the highter it is - the sharper is your image -->
<env_texture_size>1024</env_texture_size>
</lens>
<!--<distortion>-->
<!--<k1>-0.00040996368625201285</k1>-->
<!--<k2>0.03653175011277199</k2>-->
<!--<k3>0.0</k3>-->
<!--<p1>-0.034823670983314514</p1>-->
<!--<p2>0.0052825710736215115</p2>-->
<!--<center>0.5 0.5</center>-->
<!--</distortion>-->
</camera>
<plugin filename="libgazebo_ros_camera.so" name="head_t265_camerafisheye1">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>head_t265_camera/fisheye1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>head_t265_camera_fisheye1_optical_frame</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>-0.00040996368625201285</distortionK1>
<distortionK2>0.03653175011277199</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionP1>-0.034823670983314514</distortionP1>
<distortionP2>0.0052825710736215115</distortionP2>
<Cx>416.22</Cx>
<Cy>402.1</Cy>
<CxPrime>416.22</CxPrime>
</plugin>
</sensor>
</gazebo>
<gazebo reference="head_t265_camera_fisheye2_rgb_frame">
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<!--<mu>1</mu>-->
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<!--<slip1>0</slip1>
<slip2>0</slip2>-->
<kp>1e+13</kp>
<kd>1</kd>
<!--<max_vel>0.01</max_vel>
<min_depth>0</min_depth>-->
<sensor name="head_t265_camerafisheye2" type="wideanglecamera">
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
<update_rate>30</update_rate>
<camera>
<horizontal_fov>2.84</horizontal_fov>
<image>
<width>848</width>
<height>800</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<lens>
<!-- type element is mandatory -->
<type>orthographic</type>
<!-- if it is set to `true` your horizontal FOV will remain as defined -->
<!-- othervise it depends on lens type and custom function, if there is one -->
<scale_to_hfov>true</scale_to_hfov>
<!-- clip everything that is outside of this angle -->
<!-- eye balled value for these cameras-->
<cutoff_angle>2.20</cutoff_angle>
<!-- resolution of the cubemap texture, the highter it is - the sharper is your image -->
<env_texture_size>1024</env_texture_size>
</lens>
<!--<distortion>-->
<!--<k1>-0.00040996368625201285</k1>-->
<!--<k2>0.03653175011277199</k2>-->
<!--<k3>0.0</k3>-->
<!--<p1>-0.034823670983314514</p1>-->
<!--<p2>0.0052825710736215115</p2>-->
<!--<center>0.5 0.5</center>-->
<!--</distortion>-->
</camera>
<always_on>1</always_on>
<plugin filename="libgazebo_ros_camera.so" name="head_t265_camerafisheye2">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>head_t265_camera/fisheye2</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>head_t265_camera_fisheye2_optical_frame</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>-0.00040996368625201285</distortionK1>
<distortionK2>0.03653175011277199</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionP1>-0.034823670983314514</distortionP1>
<distortionP2>0.0052825710736215115</distortionP2>
</plugin>
</sensor>
</gazebo>
<joint name="head_os1_sensor_mount_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.015 0.0 0.285"/>
<parent link="head_2_link"/>
<child link="head_os1_sensor"/>
</joint>
<link name="head_os1_sensor">
<inertial>
<mass value="0.33"/>
<origin rpy="0 0 0" xyz="0 0 0.0365"/>
<inertia ixx="0.000241148" ixy="0" ixz="0" iyy="0.000241148" iyz="0" izz="0.000264"/>
</inertial>
<collision name="base_collision">
<origin rpy="0 0 0" xyz="0 0 0.0365"/>
<geometry>
<cylinder length="0.073" radius="0.04"/>
</geometry>
</collision>
<visual name="base_visual">
<origin rpy="0 0 1.5707" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/sensors/ouster/os1_64.dae"/>
<!-- <cylinder length="0.073" radius="0.04" /> -->
</geometry>
</visual>
</link>
<link name="os1_imu"/>
<link name="os1_lidar"/>
<joint name="head_os1_sensor_imu_link_joint" type="fixed">
<parent link="head_os1_sensor"/>
<child link="os1_imu"/>
<origin rpy="0 0 0" xyz="0.006253 -0.011775 0.007645"/>
</joint>
<gazebo reference="os1_imu">
</gazebo>
<joint name="head_os1_sensor_lidar_link_joint" type="fixed">
<parent link="head_os1_sensor"/>
<child link="os1_lidar"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.03618"/>
</joint>
<!-- Gazebo requires the ouster_gazebo_plugins package -->
<gazebo reference="head_os1_sensor">
<sensor name="head_os1_sensor-OS1-64" type="ray">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>220</samples>
<resolution>1</resolution>
<min_angle>-3.14159265359</min_angle>
<max_angle>3.14159265359</max_angle>
</horizontal>
<vertical>
<samples>64</samples>
<resolution>1</resolution>
<min_angle>-0.26</min_angle>
<max_angle>0.26</max_angle>
</vertical>
</scan>
<range>
<min>0.9</min>
<max>75.0</max>
<resolution>0.03</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_ouster_laser.so" name="gazebo_ros_laser_controller">
<topicName>/os1_cloud_node/points</topicName>
<frameName>os1_lidar</frameName>
<min_range>0.9</min_range>
<max_range>75.0</max_range>
<gaussianNoise>0.008</gaussianNoise>
</plugin>
</sensor>
</gazebo>
<!-- IMU -->
<gazebo>
<plugin filename="libhector_gazebo_ros_imu.so" name="imu_controller">
<robotNamespace>/</robotNamespace>
<updateRate>100.0</updateRate>
<bodyName>os1_imu</bodyName>
<topicName>/os1_cloud_node/imu</topicName>
<accelDrift>0.005 0.005 0.005</accelDrift>
<accelGaussianNoise>0.005 0.005 0.005</accelGaussianNoise>
<rateDrift>0.005 0.005 0.005 </rateDrift>
<rateGaussianNoise>0.005 0.005 0.005 </rateGaussianNoise>
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</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://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://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://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://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://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://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://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://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://talos_data/meshes/arm/arm_5.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="20.0" lower="-2.51327412287" upper="2.51327412287" 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>
<mass value="0.40931"/>
<inertia ixx="0.00010700023" ixy="-8.899e-08" ixz="-4.392e-08" iyy="0.00014101316" iyz="4.1702e-07" izz="0.00015398658"/>
<origin rpy="0 0 0" xyz="2.1e-05 -0.001965 -0.000591"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/arm/arm_6.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="8.0" lower="-1.37008346282" upper="1.37008346282" 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">
<inertial>
<mass value="0.308441"/>
<inertia ixx="0.00030894317" ixy="-1.58687e-06" ixz="1.73418e-06" iyy="0.00021886181" iyz="-1.221167e-05" izz="0.00017519492"/>
<origin rpy="0 0 0" xyz="0.007525 0.001378 -0.02463"/>
</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="8.0" lower="-0.680678408278" upper="0.680678408278" 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>
<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">
<offset>0.0</offset>
<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>
<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">
<offset>0.0</offset>
<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">
<offset>0.0</offset>
<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">
<offset>0.0</offset>
<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">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!--************************-->
<!-- SHOULDER -->
<!--************************-->
<link name="arm_right_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://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://talos_data/meshes/arm/arm_1_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="arm_right_1_joint" type="revolute">
<parent link="torso_2_link"/>
<child link="arm_right_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="-0.785398163397" upper="1.57079632679" 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_right_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://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://talos_data/meshes/arm/arm_2_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="arm_right_2_joint" type="revolute">
<parent link="arm_right_1_link"/>
<child link="arm_right_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="-2.87106661953" upper="-0.00872664625997" 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_right_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://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://talos_data/meshes/arm/arm_3_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="arm_right_3_joint" type="revolute">
<parent link="arm_right_2_link"/>
<child link="arm_right_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_right_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://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://talos_data/meshes/arm/arm_4_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="arm_right_4_joint" type="revolute">
<parent link="arm_right_3_link"/>
<child link="arm_right_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_right_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<!--************************-->
<!-- WRIST -->
<!--************************-->
<link name="arm_right_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://talos_data/meshes/arm/arm_5.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_right_5_joint" type="revolute">
<parent link="arm_right_4_link"/>
<child link="arm_right_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02000 0.00000 -0.26430"/>
<axis xyz="0 0 1"/>
<limit effort="20.0" lower="-2.51327412287" upper="2.51327412287" 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_right_6_link">
<inertial>
<mass value="0.40931"/>
<inertia ixx="0.00010700023" ixy="8.899e-08" ixz="-4.392e-08" iyy="0.00014101316" iyz="-4.1702e-07" izz="0.00015398658"/>
<origin rpy="0 0 0" xyz="2.1e-05 0.001965 -0.000591"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/arm/arm_6.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_right_6_joint" type="revolute">
<parent link="arm_right_5_link"/>
<child link="arm_right_6_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="8.0" lower="-1.37008346282" upper="1.37008346282" 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_right_7_link">
<inertial>
<mass value="0.308441"/>
<inertia ixx="0.00030894317" ixy="1.58687e-06" ixz="1.73418e-06" iyy="0.00021886181" iyz="1.221167e-05" izz="0.00017519492"/>
<origin rpy="0 0 0" xyz="0.007525 -0.001378 -0.02463"/>
</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_right_7_joint" type="revolute">
<parent link="arm_right_6_link"/>
<child link="arm_right_7_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<axis xyz="0 1 0"/>
<limit effort="8.0" lower="-0.680678408278" upper="0.680678408278" 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_right_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="arm_right_6_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="arm_right_7_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_7_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<transmission name="arm_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_5_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="wrist_right_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="arm_right_6_motor">
<role>actuator1</role>
<mechanicalReduction>-1.0</mechanicalReduction>
</actuator>
<actuator name="arm_right_7_motor">
<role>actuator2</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_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_right_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>
<transmission name="arm_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_1_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_2_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_3_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_4_joint">
<offset>0.0</offset>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!--************************-->
<!-- ft sensor -->
<!--************************-->
<link name="wrist_right_ft_link">
<inertial>
<mass value="0.095"/>
<inertia ixx="1.108502e-05" ixy="9.9077e-07" ixz="-2.3811e-07" iyy="1.092725e-05" iyz="2.3137e-07" izz="1.898772e-05"/>
<origin rpy="0 0 0" xyz="-0.001001 0.000995 -0.008108"/>
</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_right_ft_joint" type="fixed">
<parent link="arm_right_7_link"/>
<child link="wrist_right_ft_link"/>
<origin rpy="0.0 0 -1.57079632679" xyz="0 0 -0.051"/>
</joint>
<!--***********************-->
<!-- FT TOOL -->
<!--***********************-->
<link name="wrist_right_ft_tool_link">
<inertial>
<mass value="0.001"/>
<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>
<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_right_tool_joint" type="fixed">
<parent link="wrist_right_ft_link"/>
<child link="wrist_right_ft_tool_link"/>
<origin rpy="0 0 -1.57079632679" xyz="0 0 -0.012725"/>
</joint>
<!--************************-->
<!-- ft sensor -->
<!--************************-->
<link name="wrist_left_ft_link">
<inertial>
<mass value="0.095"/>
<inertia ixx="1.108502e-05" ixy="9.9077e-07" ixz="-2.3811e-07" iyy="1.092725e-05" iyz="2.3137e-07" izz="1.898772e-05"/>
<origin rpy="0 0 0" xyz="-0.001001 0.000995 -0.008108"/>
</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.001"/>
<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>
<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>
<mass value="0.637534"/>
<inertia ixx="0.0005849692" ixy="4.37159e-06" ixz="-1.2589e-05" iyy="0.00067076439" iyz="2.824361e-05" izz="0.00085526645"/>
<origin rpy="0 0 0" xyz="2.8e-05 0.005394 -0.023654"/>
</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>
<mass value="0.134356"/>
<inertia ixx="0.00013479919" ixy="6.184429e-05" ixz="-3.0798e-05" iyy="0.00019602207" iyz="4.707722e-05" izz="0.00024217879"/>
<origin rpy="0 0 0" xyz="0.019654 0.018572 -0.011998"/>
</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="-0.959931088597" upper="0.0" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="gripper_left_inner_double_link">
<inertial>
<mass value="0.087986"/>
<inertia ixx="7.410642e-05" ixy="-7.4773e-07" ixz="1.01536e-06" iyy="0.0001279418" iyz="2.504083e-05" izz="0.00010495175"/>
<origin rpy="0 0 0" xyz="-0.013283 0.036852 -0.023153"/>
</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="revolute">
<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>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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="revolute">
<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>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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="revolute">
<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>
<mass value="0.107923"/>
<inertia ixx="8.973662e-05" ixy="-4.082027e-05" ixz="-1.927099e-05" iyy="0.00011957255" iyz="-2.873284e-05" izz="0.00015469079"/>
<origin rpy="0 0 0" xyz="0.025237 -0.011231 -0.008158"/>
</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="revolute">
<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>
<mass value="0.047177"/>
<inertia ixx="4.199818e-05" ixy="1.3418e-07" ixz="1.9358e-07" iyy="3.231338e-05" iyz="-1.509136e-05" izz="2.168842e-05"/>
<origin rpy="0 0 0" xyz="0 -0.034565 -0.021412"/>
</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="revolute">
<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>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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="revolute">
<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/JointStateInterface</hardwareInterface>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</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>
<mass value="0.637534"/>
<inertia ixx="0.0005849692" ixy="4.37159e-06" ixz="-1.2589e-05" iyy="0.00067076439" iyz="2.824361e-05" izz="0.00085526645"/>
<origin rpy="0 0 0" xyz="2.8e-05 0.005394 -0.023654"/>
</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_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>
<mass value="0.134356"/>
<inertia ixx="0.00013479919" ixy="6.184429e-05" ixz="-3.0798e-05" iyy="0.00019602207" iyz="4.707722e-05" izz="0.00024217879"/>
<origin rpy="0 0 0" xyz="0.019654 0.018572 -0.011998"/>
</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_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="-0.959931088597" upper="0.0" velocity="1.0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="gripper_right_inner_double_link">
<inertial>
<mass value="0.087986"/>
<inertia ixx="7.410642e-05" ixy="-7.4773e-07" ixz="1.01536e-06" iyy="0.0001279418" iyz="2.504083e-05" izz="0.00010495175"/>
<origin rpy="0 0 0" xyz="-0.013283 0.036852 -0.023153"/>
</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_right_inner_double_joint" type="revolute">
<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>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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_right_fingertip_1_joint" type="revolute">
<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>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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_right_fingertip_2_joint" type="revolute">
<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>
<mass value="0.107923"/>
<inertia ixx="8.973662e-05" ixy="-4.082027e-05" ixz="-1.927099e-05" iyy="0.00011957255" iyz="-2.873284e-05" izz="0.00015469079"/>
<origin rpy="0 0 0" xyz="0.025237 -0.011231 -0.008158"/>
</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_right_motor_single_joint" type="revolute">
<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>
<mass value="0.047177"/>
<inertia ixx="4.199818e-05" ixy="1.3418e-07" ixz="1.9358e-07" iyy="3.231338e-05" iyz="-1.509136e-05" izz="2.168842e-05"/>
<origin rpy="0 0 0" xyz="0 -0.034565 -0.021412"/>
</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_right_inner_single_joint" type="revolute">
<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>
<mass value="0.026301"/>
<inertia ixx="8e-06" ixy="0.0" ixz="0.0" iyy="8.69179e-06" iyz="-1.43612e-06" izz="2.3082e-06"/>
<origin rpy="0 0 0" xyz="0 0.004604 -0.002537"/>
</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_right_fingertip_3_joint" type="revolute">
<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/JointStateInterface</hardwareInterface>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</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>
<mass value="1.845591"/>
<inertia ixx="0.00541533521" ixy="-0.00015428714" ixz="0.00131612622" iyy="0.00848624936" iyz="-1.906103e-05" izz="0.00474512541"/>
<origin rpy="0 0 0" xyz="0.02247868 0.00106736 0.03130665"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.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/v2/hip_z_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_left_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02 0.085 -0.27105"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-0.349065850399" upper="1.57079632679" velocity="3.87"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_left_2_link">
<inertial>
<mass value="1.490952"/>
<inertia ixx="0.00497152259" ixy="-0.0001311358" ixz="-4.86648e-06" iyy="0.00190550993" iyz="4.585381e-05" izz="0.00474289754"/>
<origin rpy="0 0 0" xyz="-0.00704703 0.02592659 0.00273385"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_2_joint" type="revolute">
<parent link="leg_left_1_link"/>
<child link="leg_left_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_left_3_link">
<inertial>
<mass value="6.239871"/>
<inertia ixx="0.15337403915" ixy="0.00068913396" ixz="0.00168034366" iyy="0.13648139346" iyz="-0.02187635445" izz="0.03001594885"/>
<origin rpy="0 0 0" xyz="0.0058523 0.0636967 -0.18339564"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.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/v2/hip_y_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_3_joint" type="revolute">
<parent link="leg_left_2_link"/>
<child link="leg_left_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_left_4_link">
<inertial>
<mass value="3.759951"/>
<inertia ixx="0.04287677484" ixy="0.00043705397" ixz="0.00078292368" iyy="0.03598906971" iyz="0.00037717694" izz="0.01364791564"/>
<origin rpy="0 0 0" xyz="0.01317717 0.02917508 -0.11594602"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.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/v2/knee_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_4_joint" type="revolute">
<parent link="leg_left_3_link"/>
<child link="leg_left_4_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="0" upper="2.618" velocity="7"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_left_5_link">
<inertial>
<mass value="1.29096"/>
<inertia ixx="0.01143430819" ixy="0.00096978273" ixz="0.00039976581" iyy="0.00888974312" iyz="-0.00277808667" izz="0.00506373875"/>
<origin rpy="0 0 0" xyz="-0.01400838 0.04180064 0.03820186"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_5_joint" type="revolute">
<parent link="leg_left_4_link"/>
<child link="leg_left_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.27" upper="0.68" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_left_6_link">
<inertial>
<mass value="1.597773"/>
<inertia ixx="0.00439027267" ixy="-6.743674e-05" ixz="0.00113816363" iyy="0.00743063029" iyz="3.943143e-05" izz="0.00550906699"/>
<origin rpy="0 0 0" xyz="-0.02034668 -0.00051514 -0.05987428"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.21 0.13 0.02"/>
</geometry>
</collision>
</link>
<joint name="leg_left_6_joint" type="revolute">
<parent link="leg_left_5_link"/>
<child link="leg_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="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- from here is copy paste -->
<link name="left_sole_link">
<inertial>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<joint name="leg_left_sole_fix_joint" type="fixed">
<parent link="leg_left_6_link"/>
<child link="left_sole_link"/>
<origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<transmission name="leg_left_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_6_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_6_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_6_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="leg_left_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_left_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_left_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_left_6_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
<link name="leg_right_1_link">
<inertial>
<mass value="1.845591"/>
<inertia ixx="0.00541533521" ixy="0.00015428714" ixz="0.00131612622" iyy="0.00848624936" iyz="1.906103e-05" izz="0.00474512541"/>
<origin rpy="0 0 0" xyz="0.02247868 -0.00106736 0.03130665"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.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/v2/hip_z_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_right_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02 -0.085 -0.27105"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-1.57079632679" upper="0.349065850399" velocity="3.87"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_right_2_link">
<inertial>
<mass value="1.490952"/>
<inertia ixx="0.00497152259" ixy="0.0001311358" ixz="-4.86648e-06" iyy="0.00190550993" iyz="-4.585381e-05" izz="0.00474289754"/>
<origin rpy="0 0 0" xyz="-0.00704703 -0.02592659 0.00273385"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_2_joint" type="revolute">
<parent link="leg_right_1_link"/>
<child link="leg_right_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_right_3_link">
<inertial>
<mass value="6.239871"/>
<inertia ixx="0.15337403915" ixy="-0.00068913396" ixz="0.00168034366" iyy="0.13648139346" iyz="0.02187635445" izz="0.03001594885"/>
<origin rpy="0 0 0" xyz="0.0058523 -0.0636967 -0.18339564"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.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/v2/hip_y_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_3_joint" type="revolute">
<parent link="leg_right_2_link"/>
<child link="leg_right_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_right_4_link">
<inertial>
<mass value="3.759951"/>
<inertia ixx="0.04287677484" ixy="-0.00043705397" ixz="0.00078292368" iyy="0.03598906971" iyz="-0.00037717694" izz="0.01364791564"/>
<origin rpy="0 0 0" xyz="0.01317717 -0.02917508 -0.11594602"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.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/v2/knee_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_4_joint" type="revolute">
<parent link="leg_right_3_link"/>
<child link="leg_right_4_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="0" upper="2.618" velocity="7"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_right_5_link">
<inertial>
<mass value="1.29096"/>
<inertia ixx="0.01143430819" ixy="-0.00096978273" ixz="0.00039976581" iyy="0.00888974312" iyz="0.00277808667" izz="0.00506373875"/>
<origin rpy="0 0 0" xyz="-0.01400838 -0.04180064 0.03820186"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_5_joint" type="revolute">
<parent link="leg_right_4_link"/>
<child link="leg_right_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.27" upper="0.68" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_right_6_link">
<inertial>
<mass value="1.597773"/>
<inertia ixx="0.00439027267" ixy="6.743674e-05" ixz="0.00113816363" iyy="0.00743063029" iyz="-3.943143e-05" izz="0.00550906699"/>
<origin rpy="0 0 0" xyz="-0.02034668 0.00051514 -0.05987428"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 -1 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.21 0.13 0.02"/>
</geometry>
</collision>
</link>
<joint name="leg_right_6_joint" type="revolute">
<parent link="leg_right_5_link"/>
<child link="leg_right_6_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- from here is copy paste -->
<link name="right_sole_link">
<inertial>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<joint name="leg_right_sole_fix_joint" type="fixed">
<parent link="leg_right_6_link"/>
<child link="right_sole_link"/>
<origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<transmission name="leg_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_6_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_6_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_6_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="leg_right_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_right_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_right_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_right_6_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<ns/>
<robotSimType>pal_hardware_gazebo/PalHardwareGazebo</robotSimType>
<robotNamespace/>
<controlPeriod>0.001</controlPeriod>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_world_odometry.so" name="gazebo_ros_odometry">
<frameName>base_link</frameName>
<topicName>floating_base_pose_simulated</topicName>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
<bodyName>base_link</bodyName>
<topicName>wrench</topicName>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<!-- this is expected to be reparented to pelvis with appropriate offset
when imu_link is reduced by fixed joint reduction -->
<!-- todo: this is working with gazebo 1.4, need to write a unit test -->
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1000.0</update_rate>
<imu>
<noise>
<type>gaussian</type>
<!-- Noise parameters from Boston Dynamics
(http://gazebosim.org/wiki/Sensor_noise):
rates (rad/s): mean=0, stddev=2e-4
accels (m/s/s): mean=0, stddev=1.7e-2
rate bias (rad/s): 5e-6 - 1e-5
accel bias (m/s/s): 1e-1
Experimentally, simulation provide rates with noise of
about 1e-3 rad/s and accels with noise of about 1e-1 m/s/s.
So we don't expect to see the noise unless number of inner iterations
are increased.
We will add bias. In this model, bias is sampled once for rates
and once for accels at startup; the sign (negative or positive)
of each bias is then switched with equal probability. Thereafter,
the biases are fixed additive offsets. We choose
bias means and stddevs to produce biases close to the provided
data. -->
<!--
<rate>
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
-->
<rate>
<mean>0.0</mean>
<stddev>0.0</stddev>
<bias_mean>0.000000</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>0.0</stddev>
<bias_mean>0.0</bias_mean>
<bias_stddev>0.000</bias_stddev>
</accel>
</noise>
</imu>
</sensor>
</gazebo>
<!-- define global properties -->
<!-- <xacro:property name="M_PI" value="3.1415926535897931" /> -->
<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>
../robots/talos_reduced.urdf
\ No newline at end of file
<?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">
<!--File includes-->
<!--Constant parameters-->
<!--File includes-->
<!-- Macro -->
<!--Constant parameters-->
<!--************************-->
<!-- HEAD_1 (TILT) -->
<!--************************-->
<!--************************-->
<!-- HEAD_2 (PAN) -->
<!--************************-->
<!--File includes-->
<!--File includes-->
<!--Constant parameters-->
<!--Constant parameters-->
<!--File includes-->
<!-- VIRTUAL (mimic) JOINTS -->
<!-- 0.45deg -->
<!--************************-->
<!-- TORSO_2 (TILT) -->
<!--************************-->
<link name="torso_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.04551 -0.00053 0.16386"/>
<mass value="17.55011"/>
<inertia ixx="0.37376900000" ixy="0.00063900000" ixz="0.01219600000" iyy="0.24790200000" iyz="0.00000700000" izz="0.28140400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://talos_data/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<!--************************-->
<!-- TORSO_1 (PAN) -->
<!--************************-->
<link name="torso_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00013 -0.00001 -0.01306"/>
<mass value="3.02433"/>
<inertia ixx="0.00759400000" ixy="0.00000100000" ixz="-0.00004800000" iyy="0.00429200000" iyz="-0.00000100000" izz="0.00749700000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0722"/>
<axis xyz="0 0 1"/>
<limit effort="78.0" lower="-1.308996939" upper="1.308996939" 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>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.08222 0.00838 -0.07261"/>
<mass value="13.53810"/>
<inertia ixx="0.06989000000" ixy="-0.00011700000" ixz="0.00023000000" iyy="0.03998200000" iyz="-0.00132500000" izz="0.08234500000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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="78.0" lower="-0.261799387799" upper="0.785398163397" 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"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.000001"/>
</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>
<!-- extensions -->
<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>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00120 0.00145 0.02165"/>
<mass value="0.65988"/>
<inertia ixx="0.00122100000" ixy="-0.00000400000" ixz="0.00007000000" iyy="0.00092400000" iyz="-0.00004100000" izz="0.00103300000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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.00000 0.00000 0.31600"/>
<axis xyz="0 1 0"/>
<limit effort="8.0" lower="-0.261799387799" 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>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01036 -0.00037 0.13778"/>
<mass value="1.40353"/>
<inertia ixx="0.00722500000" ixy="-0.00002500000" ixz="0.00032900000" iyy="0.00687300000" iyz="0.00004400000" izz="0.00437300000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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://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" 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"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<!-- inertia tensor computed analytically for a solid cuboid -->
<inertia ixx="0.000030" ixy="0.0" ixz="0.0" iyy="0.000030" iyz="0.0" izz="0.000002"/>
</inertial>
<!--
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://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"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="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"/>
<!-- extensions -->
<gazebo reference="rgbd_link">
<!-- IR + depth -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>6.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.45</near>
<far>10.0</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>6.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>ir/image_raw</imageTopicName>
<cameraInfoTopicName>ir/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>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
</plugin>
</sensor>
<!-- RGB -->
<sensor name="rgbd_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>6.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.45</near>
<far>10.0</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>6.0</updateRate>
<cameraName>rgbd</cameraName>
<imageTopicName>rgb/image_raw</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<pointCloudTopicName>rgb/points</pointCloudTopicName>
<frameName>rgbd_optical_frame</frameName>
<pointCloudCutoff>0.45</pointCloudCutoff>
<rangeMax>10.0</rangeMax>
<distalostionK1>0.00000001</distalostionK1>
<distalostionK2>0.00000001</distalostionK2>
<distalostionK3>0.00000001</distalostionK3>
<distalostionT1>0.00000001</distalostionT1>
<distalostionT2>0.00000001</distalostionT2>
</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">
<!-- 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>
<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"/>
<limit effort="44.64" lower="-1.57079632679" upper="0.523598775598" 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>
<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>
<!--************************-->
<!-- SHOULDER -->
<!--************************-->
<link name="arm_right_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>
<joint name="arm_right_1_joint" type="revolute">
<parent link="torso_2_link"/>
<child link="arm_right_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.1575 0.23200"/>
<axis xyz="0 0 1"/>
<limit effort="44.64" lower="-0.523598775598" upper="1.57079632679" 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_right_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_right_2_joint" type="revolute">
<parent link="arm_right_1_link"/>
<child link="arm_right_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="-2.87979326579" upper="0.0" 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_right_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_right_3_joint" type="revolute">
<parent link="arm_right_2_link"/>
<child link="arm_right_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_right_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_right_4_joint" type="revolute">
<parent link="arm_right_3_link"/>
<child link="arm_right_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_right_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<!--************************-->
<!-- WRIST -->
<!--************************-->
<!--************************-->
<!-- WRIST -->
<!--************************-->
<link name="arm_right_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_right_5_joint" type="revolute">
<parent link="arm_right_4_link"/>
<child link="arm_right_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_right_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_right_6_joint" type="revolute">
<parent link="arm_right_5_link"/>
<child link="arm_right_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_right_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_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_7_collision.STL" scale="1 -1 1"/>
</geometry>
</collision>
</link>
<joint name="arm_right_7_joint" type="revolute">
<parent link="arm_right_6_link"/>
<child link="arm_right_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_right_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="arm_right_6_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="arm_right_7_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="arm_right_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="arm_right_7_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<!-- extensions -->
<transmission name="arm_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="wrist_right_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="arm_right_6_motor">
<role>actuator1</role>
<mechanicalReduction>-1.0</mechanicalReduction>
</actuator>
<actuator name="arm_right_7_motor">
<role>actuator2</role>
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_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_right_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_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="arm_right_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="arm_right_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="arm_right_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<!--************************-->
<!-- ft sensor -->
<!--************************-->
<link name="wrist_right_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_right_ft_joint" type="fixed">
<parent link="arm_right_7_link"/>
<child link="wrist_right_ft_link"/>
<origin rpy="0.0 0 -1.57079632679" xyz="0 0 -0.051"/>
</joint>
<!--***********************-->
<!-- FT TOOL -->
<!--***********************-->
<link name="wrist_right_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_right_tool_joint" type="fixed">
<parent link="wrist_right_ft_link"/>
<child link="wrist_right_ft_tool_link"/>
<origin rpy="0 0 -1.57079632679" xyz="0 0 -0.012725"/>
</joint>
<!--************************-->
<!-- 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"/> -->
<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_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_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_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_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_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_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_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_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_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_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_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_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_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_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_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_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>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
<mass value="1.88569"/>
<inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.stl" scale="1 1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_collision.stl" scale="1 1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_left_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02 0.085 -0.27105"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-0.349065850399" upper="1.57079632679" velocity="3.87"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_left_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
<mass value="2.37607"/>
<inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_2_joint" type="revolute">
<parent link="leg_left_1_link"/>
<child link="leg_left_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_left_3_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 0.06563 -0.17278"/>
<mass value="6.82734"/>
<inertia ixx="0.12390600000" ixy="-0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="0.016725" izz="0.02781200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.stl" scale="1 1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_collision.stl" scale="1 1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_3_joint" type="revolute">
<parent link="leg_left_2_link"/>
<child link="leg_left_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_left_4_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 0.02331 -0.12063"/>
<mass value="3.63668"/>
<inertia ixx="0.03531500000" ixy="2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="-0.001305" izz="0.01174000000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.stl" scale="1 1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_collision.stl" scale="1 1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_4_joint" type="revolute">
<parent link="leg_left_3_link"/>
<child link="leg_left_4_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="0" upper="2.618" velocity="7"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_left_5_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 0.04708 0.05271"/>
<mass value="1.24433"/>
<inertia ixx="0.01148700000" ixy="-0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="0.002633" izz="0.00390800000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 1.0 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_left_5_joint" type="revolute">
<parent link="leg_left_4_link"/>
<child link="leg_left_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_left_6_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
<mass value="1.59457"/>
<inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 1.0 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 1 1"/>
</geometry>
</collision>
<!--
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.21 0.13 0.02"/>
</geometry>
</collision>
-->
</link>
<joint name="leg_left_6_joint" type="revolute">
<parent link="leg_left_5_link"/>
<child link="leg_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="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- from here is copy paste -->
<link name="left_sole_link">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>
<joint name="leg_left_sole_fix_joint" type="fixed">
<parent link="leg_left_6_link"/>
<child link="left_sole_link"/>
<origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<transmission name="leg_left_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_left_6_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_left_6_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_left_6_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="leg_left_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_left_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_left_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_left_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_left_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_left_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_left_6_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
<link name="leg_right_1_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
<mass value="1.88569"/>
<inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_lo_res.stl" scale="1 -1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_z_collision.stl" scale="1 -1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_1_joint" type="revolute">
<parent link="base_link"/>
<child link="leg_right_1_link"/>
<origin rpy="0.0 0.0 0.0" xyz="-0.02 -0.085 -0.27105"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-1.57079632679" upper="0.349065850399" velocity="3.87"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
<link name="leg_right_2_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
<mass value="2.37607"/>
<inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 -1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_x_collision.stl" scale="1 -1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_2_joint" type="revolute">
<parent link="leg_right_1_link"/>
<child link="leg_right_2_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
<link name="leg_right_3_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 -0.06563 -0.17278"/>
<mass value="6.82734"/>
<inertia ixx="0.12390600000" ixy="0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="-0.016725" izz="0.02781200000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_lo_res.stl" scale="1 -1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/hip_y_collision.stl" scale="1 -1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_3_joint" type="revolute">
<parent link="leg_right_2_link"/>
<child link="leg_right_3_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
<link name="leg_right_4_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 -0.02331 -0.12063"/>
<mass value="3.63668"/>
<inertia ixx="0.03531500000" ixy="-2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="0.001305" izz="0.01174000000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_lo_res.stl" scale="1 -1.0 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/knee_collision.stl" scale="1 -1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_4_joint" type="revolute">
<parent link="leg_right_3_link"/>
<child link="leg_right_4_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
<axis xyz="0 1 0"/>
<limit effort="300" lower="0" upper="2.618" velocity="7"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
<link name="leg_right_5_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 -0.04708 0.05271"/>
<mass value="1.24433"/>
<inertia ixx="0.01148700000" ixy="0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="-0.002633" izz="0.00390800000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 -1.0 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 -1.0 1"/>
</geometry>
</collision>
</link>
<joint name="leg_right_5_joint" type="revolute">
<parent link="leg_right_4_link"/>
<child link="leg_right_5_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
<axis xyz="0 1 0"/>
<limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
<link name="leg_right_6_link">
<inertial>
<origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
<mass value="1.59457"/>
<inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 -1.0 1"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 -1 1"/>
</geometry>
</collision>
<!--
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.21 0.13 0.02"/>
</geometry>
</collision>
-->
</link>
<joint name="leg_right_6_joint" type="revolute">
<parent link="leg_right_5_link"/>
<child link="leg_right_6_link"/>
<origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
<axis xyz="1 0 0"/>
<limit effort="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<!-- from here is copy paste -->
<link name="right_sole_link">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>
<joint name="leg_right_sole_fix_joint" type="fixed">
<parent link="leg_right_6_link"/>
<child link="right_sole_link"/>
<origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<transmission name="leg_right_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_1_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_2_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_3_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_4_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_4_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_4_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_5_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_5_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_5_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="leg_right_6_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="leg_right_6_motor">
<mechanicalReduction>1.0</mechanicalReduction>
</actuator>
<joint name="leg_right_6_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="leg_right_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_3_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_4_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="leg_right_5_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<!-- contact model for foot surface -->
<gazebo reference="leg_right_6_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_3_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_4_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_5_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="leg_right_6_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<gazebo reference="leg_right_1_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_2_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_3_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_4_link">
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="leg_right_5_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="leg_right_6_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Generic simulatalos_gazebo plugins -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<ns/>
<robotSimType>pal_hardware_gazebo/PalHardwareGazebo</robotSimType>
<robotNamespace/>
<controlPeriod>0.001</controlPeriod>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_world_odometry.so" name="gazebo_ros_odometry">
<frameName>base_link</frameName>
<topicName>floating_base_pose_simulated</topicName>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
<bodyName>base_link</bodyName>
<topicName>wrench</topicName>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<!-- this is expected to be reparented to pelvis with appropriate offset
when imu_link is reduced by fixed joint reduction -->
<!-- todo: this is working with gazebo 1.4, need to write a unit test -->
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1000.0</update_rate>
<imu>
<noise>
<type>gaussian</type>
<!-- Noise parameters from Boston Dynamics
(http://gazebosim.org/wiki/Sensor_noise):
rates (rad/s): mean=0, stddev=2e-4
accels (m/s/s): mean=0, stddev=1.7e-2
rate bias (rad/s): 5e-6 - 1e-5
accel bias (m/s/s): 1e-1
Experimentally, simulation provide rates with noise of
about 1e-3 rad/s and accels with noise of about 1e-1 m/s/s.
So we don't expect to see the noise unless number of inner iterations
are increased.
We will add bias. In this model, bias is sampled once for rates
and once for accels at startup; the sign (negative or positive)
of each bias is then switched with equal probability. Thereafter,
the biases are fixed additive offsets. We choose
bias means and stddevs to produce biases close to the provided
data. -->
<!--
<rate>
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</accel>
-->
<rate>
<mean>0.0</mean>
<stddev>0.0</stddev>
<bias_mean>0.000000</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</rate>
<accel>
<mean>0.0</mean>
<stddev>0.0</stddev>
<bias_mean>0.0</bias_mean>
<bias_stddev>0.000</bias_stddev>
</accel>
</noise>
</imu>
</sensor>
</gazebo>
<!-- 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>