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

Add new gripper model

parent b642a25c
No related branches found
No related tags found
No related merge requests found
Showing with 230 additions and 11 deletions
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="talos" 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 talos_description)/urdf/gripper/gripper_v2.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/torso/torso.urdf.xacro" />
<xacro:talos_torso name="torso" />
<xacro:talos_gripper name="gripper" parent="torso_2_link"/>
<!-- 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" />
</robot>
<launch>
<!-- Robot description -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find talos_description)/robots/talos_gripper.urdf.xacro'" />
</launch>
......@@ -3,8 +3,8 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!--File includes-->
<!-- <xacro:include filename="$(find talos_description)/urdf/deg_to_rad.urdf.xacro" />
<xacro:include filename="$(find talos_description)/urdf/gripper.transmission.xacro" />
<xacro:include filename="$(find talos_description)/urdf/deg_to_rad.xacro" />
<!-- <xacro:include filename="$(find talos_description)/urdf/gripper.transmission.xacro" />
<xacro:include filename="$(find talos_description)/urdf/gripper.gazebo.xacro" /> -->
......@@ -24,6 +24,7 @@
<geometry>
<mesh filename="package://talos_description/meshes/gripper/base_link.STL" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
......@@ -41,8 +42,6 @@
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${90.00000 * deg_to_rad}"/>
<axis xyz="0 0 0" />
</joint>
<!-- Joint gripper_motor_double (None) : child link -- -> parent link gripper_base_link -->
<link name="${name}_motor_double_link">
......@@ -59,6 +58,7 @@
<geometry>
<mesh filename="package://talos_description/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
......@@ -72,11 +72,10 @@
<joint name="${name}_motor_double_joint" type="revolute">
<parent link="${name}_base_link"/>
<child link="${name}_motor_double_link"/>
<origin xyz="0.00000 0.02025 -0.03000"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<!-- You may want to change axis -->
<axis xyz="0 0 1" />
<limit lower="${0.00000 * deg_to_rad}" upper="${60.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<origin xyz="0.0 0.02025 -0.03"
rpy="${0.0 * deg_to_rad} ${0.0 * deg_to_rad} ${0.0 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="${-60.0 * deg_to_rad}" upper="${0.0 * deg_to_rad}" effort="1.0" velocity="1.0" />
<dynamics friction="1.0" damping="1.0"/>
</joint>
......@@ -95,6 +94,7 @@
<geometry>
<mesh filename="package://talos_description/meshes/gripper/inner_double.STL" scale="1 1 1"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
......@@ -110,14 +110,198 @@
<child link="${name}_inner_double_link"/>
<origin xyz="0.00000 0.00525 -0.05598"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<!-- You may want to change axis -->
<axis xyz="0 0 1" />
<axis xyz="1 0 0" />
<limit lower="${0.00000 * deg_to_rad}" upper="${0.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<mimic joint="${name}_motor_double_joint" multiplier="${1.0}" offset="0.0" />
</joint>
<link name="${name}_fingertip_1_link">
<inertial>
<origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="fingertip_1_joint" type="revolute">
<parent link="${name}_inner_double_link"/>
<child link="${name}_fingertip_1_link"/>
<origin xyz="0.03200 0.04589 -0.06553"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="${0.00000 * deg_to_rad}" upper="${0.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<mimic joint="${name}_motor_double_joint" multiplier="${-1.0}" offset="0.0" />
</joint>
<link name="${name}_fingertip_2_link">
<inertial>
<origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="${name}_fingertip_2_joint" type="revolute">
<parent link="${name}_inner_double_link"/>
<child link="${name}_fingertip_2_link"/>
<origin xyz="-0.03200 0.04589 -0.06553"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="${0.00000 * deg_to_rad}" upper="${0.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<mimic joint="${name}_motor_double_joint" multiplier="${-1.0}" offset="0.0" />
</joint>
<link name="${name}_motor_single_link">
<inertial>
<origin xyz="0.02589 -0.01284 -0.00640" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="${name}_motor_single_joint" type="revolute">
<parent link="${name}_base_link"/>
<child link="${name}_motor_single_link"/>
<origin xyz="0.00000 -0.02025 -0.03000"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="${0.00000 * deg_to_rad}" upper="${0.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<mimic joint="${name}_motor_double_joint" multiplier="${-1.0}" offset="0.0" />
</joint>
<link name="${name}_inner_single_link">
<inertial>
<origin xyz="0.00000 -0.03253 -0.01883" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/inner_single.STL" scale="1 1 1"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="${name}_inner_single_joint" type="revolute">
<parent link="${name}_base_link"/>
<child link="${name}_inner_single_link"/>
<origin xyz="0.00000 -0.00525 -0.05598"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="${0.00000 * deg_to_rad}" upper="${0.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<mimic joint="${name}_motor_double_joint" multiplier="${-1.0}" offset="0.0" />
</joint>
<link name="${name}_fingertip_3_link">
<inertial>
<origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/>
<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 xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
</geometry>
</collision>
</link>
<joint name="${name}_fingertip_3_joint" type="revolute">
<parent link="${name}_inner_single_link"/>
<child link="${name}_fingertip_3_link"/>
<origin xyz="0.00000 -0.04589 -0.06553"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${180.00000 * deg_to_rad}"/>
<axis xyz="1 0 0" />
<limit lower="${0.00000 * deg_to_rad}" upper="${0.00000 * deg_to_rad}" effort="1.0" velocity="1.0" />
<mimic joint="${name}_motor_double_joint" multiplier="${-1.0}" offset="0.0" />
</joint>
</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