Skip to content
Snippets Groups Projects
Commit 03557791 authored by Sam Pfeiffer's avatar Sam Pfeiffer
Browse files

Add torso

parent 35901f01
No related branches found
No related tags found
No related merge requests found
File added
File added
File added
File added
File added
<?xml version="1.0"?>
<!--
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="tor" xmlns:xacro="http://www.ros.org/wiki/xacro"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<xacro:include filename="$(find tor_description)/urdf/torso/torso.urdf.xacro" />
<xacro:tor_torso name="torso" />
<!-- Generic simulator_gazebo plugins -->
<xacro:include filename="$(find tor_description)/gazebo/gazebo.urdf.xacro" />
<!-- Materials for visualization -->
<xacro:include filename="$(find tor_description)/urdf/materials.urdf.xacro" />
</robot>
<launch>
<!-- Robot description -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find tor_description)/robots/tor_torso.urdf.xacro'" />
</launch>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<property name="deg_to_rad" value="0.01745329251994329577" />
</robot>
<?xml version="1.0"?>
<!--
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 xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="tor_torso_differential_transmission"
params="name number1 number2 act_reduction1 act_reduction2 jnt_reduction1 jnt_reduction2" >
<transmission name="torso_trans">
<type>transmission_interface/DifferentialTransmission</type>
<actuator name="${name}_${number1}_motor">
<role>actuator1</role>
<mechanicalReduction>${act_reduction1}</mechanicalReduction>
</actuator>
<actuator name="${name}_${number2}_motor">
<role>actuator2</role>
<mechanicalReduction>${act_reduction2}</mechanicalReduction>
</actuator>
<joint name="${name}_${number1}_joint">
<role>joint1</role>
<offset>0.0</offset>
<mechanicalReduction>${jnt_reduction1}</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<joint name="${name}_${number2}_joint">
<role>joint2</role>
<offset>0.0</offset>
<mechanicalReduction>${jnt_reduction2}</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>
</xacro:macro>
</robot>
<?xml version="1.0"?>
<!--
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 xmlns:xacro="http://ros.org/wiki/xacro">
<!--File includes-->
<xacro:include filename="$(find tor_description)/urdf/deg_to_rad.xacro" />
<xacro:include filename="$(find tor_description)/urdf/torso/torso.transmission.xacro" />
<!--Constant parameters-->
<xacro:property name="torso_max_vel" value="5.4" />
<xacro:property name="torso_max_effort" value="78.0" />
<xacro:property name="torso_eps" value="0.02" />
<xacro:macro name="tor_torso" params="name">
<!--************************-->
<!-- TORSO_2 -->
<!--************************-->
<link name="${name}_2_link">
<inertial>
<origin xyz="-0.04551 -0.00053 0.16386" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://tor_description/meshes/torso/torso_2.STL" scale="1 1 1"/>
</geometry>
<material name="LightGrey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://tor_description/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<!--************************-->
<!-- TORSO_1 -->
<!--************************-->
<link name="${name}_1_link">
<inertial>
<origin xyz="0.00013 -0.00001 -0.01306" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://tor_description/meshes/torso/torso_1.STL" scale="1 1 1"/>
</geometry>
<material name="LightGrey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://tor_description/meshes/torso/torso_1.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="${name}_1_joint" type="revolute">
<parent link="${name}_2_link"/>
<child link="${name}_1_link"/>
<origin xyz="0.02000 0.00000 0.0"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 1 0" />
<limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}"
effort="${torso_max_effort}" velocity="${torso_max_vel}"/>
<dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20"
k_velocity="20"
soft_lower_limit="${-75.0 * deg_to_rad + torso_eps}"
soft_upper_limit="${ 75.0 * deg_to_rad - torso_eps}" /> -->
</joint>
<!--************************-->
<!-- BASE_LINK -->
<!--************************-->
<link name="base_link">
<inertial>
<origin xyz="-0.06071 0.00861 0.06368" rpy="0.00000 0.00000 0.00000"/>
<mass value="13.34865"/>
<inertia ixx="0.06652900000" ixy="-0.00035700000" ixz="0.00027600000"
iyy="0.03746500000" iyz="-0.00125400000"
izz="0.07895100000"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://tor_description/meshes/torso/base_link.STL" scale="1 1 1"/>
</geometry>
<material name="LightGrey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://tor_description/meshes/torso/base_link_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="${name}_2_joint" type="revolute">
<parent link="${name}_1_link"/>
<child link="base_link"/>
<!-- <child link="${name}_2_link"/> -->
<origin xyz="0.0 0.0 -0.2012"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 0 1" />
<limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}"
effort="${torso_max_effort}" velocity="${torso_max_vel}" />
<dynamics friction="1.0" damping="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>
<!-- <joint name="torso_1_to_base_link" type="fixed">
<parent link="${name}_1_link"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.0"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 0 0" />
</joint> -->
<gazebo reference="${name}_1_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="${name}_2_link">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
</gazebo>
<gazebo reference="${name}_1_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="${name}_2_joint">
<implicitSpringDamper>1</implicitSpringDamper>
<provideFeedback>1</provideFeedback>
</gazebo>
<!-- extensions -->
<xacro:tor_torso_differential_transmission name="${name}" number1="1" number2="2"
act_reduction1="1.0" act_reduction2="1.0"
jnt_reduction1="1.0" jnt_reduction2="1.0" />
</xacro:macro>
</robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment