initial forking commit
This commit is contained in:
32
end_effectors/common/ee_with_one_link.xacro
Normal file
32
end_effectors/common/ee_with_one_link.xacro
Normal file
@@ -0,0 +1,32 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="ee_with_one_link">
|
||||
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
|
||||
<xacro:macro name="ee_with_one_link" params="connected_to:='' arm_id arm_prefix:='' ee_id ee_inertials rpy_ee:='0 0 0' xyz_ee:='0 0 0' tcp_xyz:='0 0 0' tcp_rpy:='0 0 0' safety_distance:=0 gazebo:=false description_pkg:=franka_description with_sc:=false">
|
||||
<xacro:property name="ee_prefix" default="robot_"/>
|
||||
<xacro:unless value="${arm_id == ''}">
|
||||
<xacro:property name="ee_prefix" value="${arm_prefix}${arm_id}_" />
|
||||
</xacro:unless>
|
||||
<xacro:unless value="${connected_to == ''}">
|
||||
<joint name="${ee_prefix}${ee_id}_joint" type="fixed">
|
||||
<parent link="${connected_to}" />
|
||||
<child link="${ee_prefix}${ee_id}" />
|
||||
<origin xyz="${xyz_ee}" rpy="${rpy_ee}" />
|
||||
</joint>
|
||||
</xacro:unless>
|
||||
|
||||
<xacro:ee_link_with_sc name="${ee_id}" gazebo="${gazebo}" with_sc="${with_sc}">
|
||||
<self_collision_geometries>
|
||||
<xacro:collision_capsule xyz="0 0 0.04" direction="y" radius="${0.04+safety_distance}" length="0.1" />
|
||||
<xacro:collision_capsule xyz="0 0 0.10" direction="y" radius="${0.02+safety_distance}" length="0.1" />
|
||||
</self_collision_geometries>
|
||||
</xacro:ee_link_with_sc>
|
||||
|
||||
<!-- Define the ${ee_id}_tcp frame -->
|
||||
<link name="${ee_prefix}${ee_id}_tcp" />
|
||||
<joint name="${ee_prefix}${ee_id}_tcp_joint" type="fixed">
|
||||
<origin xyz="${tcp_xyz}" rpy="${tcp_rpy}" />
|
||||
<parent link="${ee_prefix}${ee_id}" />
|
||||
<child link="${ee_prefix}${ee_id}_tcp" />
|
||||
</joint>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
126
end_effectors/common/franka_hand.xacro
Normal file
126
end_effectors/common/franka_hand.xacro
Normal file
@@ -0,0 +1,126 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
|
||||
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
|
||||
<xacro:macro name="franka_hand" params="connected_to:='' arm_id arm_prefix:='' ee_id ee_inertials rpy_ee:='0 0 0' xyz_ee:='0 0 0' tcp_xyz:='0 0 0.1034' tcp_rpy:='0 0 0' safety_distance:=0 gazebo:=false description_pkg:=franka_description with_sc:=false">
|
||||
<xacro:property name="ee_prefix" default="robot_"/>
|
||||
<xacro:unless value="${arm_id == ''}">
|
||||
<xacro:property name="ee_prefix" value="${arm_prefix}${arm_id}_" />
|
||||
</xacro:unless>
|
||||
<xacro:unless value="${connected_to == ''}">
|
||||
<joint name="${ee_prefix}hand_joint" type="fixed">
|
||||
<parent link="${connected_to}" />
|
||||
<child link="${ee_prefix}hand" />
|
||||
<origin xyz="${xyz_ee}" rpy="${rpy_ee}" />
|
||||
</joint>
|
||||
</xacro:unless>
|
||||
|
||||
<xacro:ee_link_with_sc name="hand" gazebo="${gazebo}" with_sc="${with_sc}">
|
||||
<self_collision_geometries>
|
||||
<xacro:collision_capsule xyz="0 0 0.04" direction="y" radius="${0.04+safety_distance}" length="0.1" />
|
||||
<xacro:collision_capsule xyz="0 0 0.10" direction="y" radius="${0.02+safety_distance}" length="0.1" />
|
||||
</self_collision_geometries>
|
||||
</xacro:ee_link_with_sc>
|
||||
|
||||
<!-- Define the hand_tcp frame -->
|
||||
<link name="${ee_prefix}hand_tcp" />
|
||||
<joint name="${ee_prefix}hand_tcp_joint" type="fixed">
|
||||
<origin xyz="${tcp_xyz}" rpy="${tcp_rpy}" />
|
||||
<parent link="${ee_prefix}hand" />
|
||||
<child link="${ee_prefix}hand_tcp" />
|
||||
</joint>
|
||||
<link name="${ee_prefix}leftfinger">
|
||||
<visual name="${ee_prefix}leftfinger_visual">
|
||||
<geometry>
|
||||
<mesh filename="package://${description_pkg}/meshes/robot_ee/${ee_id}/visual/finger.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<!-- screw mount -->
|
||||
<collision>
|
||||
<origin xyz="0 18.5e-3 11e-3" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="22e-3 15e-3 20e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- cartriage sledge -->
|
||||
<collision>
|
||||
<origin xyz="0 6.8e-3 2.2e-3" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="22e-3 8.8e-3 3.8e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- diagonal finger -->
|
||||
<collision>
|
||||
<origin xyz="0 15.9e-3 28.35e-3" rpy="${pi/6} 0 0" />
|
||||
<geometry>
|
||||
<box size="17.5e-3 7e-3 23.5e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- rubber tip with which to grasp -->
|
||||
<collision>
|
||||
<origin xyz="0 7.58e-3 45.25e-3" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="17.5e-3 15.2e-3 18.5e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:if value="${gazebo}">
|
||||
<xacro:ee-inertials name="leftfinger" />
|
||||
</xacro:if>
|
||||
</link>
|
||||
<link name="${ee_prefix}rightfinger">
|
||||
<visual name="${ee_prefix}rightfinger_visual">
|
||||
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
|
||||
<geometry>
|
||||
<mesh filename="package://${description_pkg}/meshes/robot_ee/${ee_id}/visual/finger.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<!-- screw mount -->
|
||||
<collision>
|
||||
<origin xyz="0 -18.5e-3 11e-3" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="22e-3 15e-3 20e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- cartriage sledge -->
|
||||
<collision>
|
||||
<origin xyz="0 -6.8e-3 2.2e-3" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="22e-3 8.8e-3 3.8e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- diagonal finger -->
|
||||
<collision>
|
||||
<origin xyz="0 -15.9e-3 28.35e-3" rpy="${-pi/6} 0 0" />
|
||||
<geometry>
|
||||
<box size="17.5e-3 7e-3 23.5e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<!-- rubber tip with which to grasp -->
|
||||
<collision>
|
||||
<origin xyz="0 -7.58e-3 45.25e-3" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="17.5e-3 15.2e-3 18.5e-3" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:if value="${gazebo}">
|
||||
<xacro:ee-inertials name="rightfinger" />
|
||||
</xacro:if>
|
||||
</link>
|
||||
<joint name="${ee_prefix}finger_joint1" type="prismatic">
|
||||
<parent link="${ee_prefix}hand" />
|
||||
<child link="${ee_prefix}leftfinger" />
|
||||
<origin xyz="0 0 0.0584" rpy="0 0 0" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit effort="100" lower="0.0" upper="0.04" velocity="0.2" />
|
||||
<dynamics damping="0.3" />
|
||||
</joint>
|
||||
<joint name="${ee_prefix}finger_joint2" type="prismatic">
|
||||
<parent link="${ee_prefix}hand" />
|
||||
<child link="${ee_prefix}rightfinger" />
|
||||
<origin xyz="0 0 0.0584" rpy="0 0 0" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit effort="100" lower="0.0" upper="0.04" velocity="0.2" />
|
||||
<mimic joint="${ee_prefix}finger_joint1" />
|
||||
<dynamics damping="0.3" />
|
||||
</joint>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
111
end_effectors/common/utils.xacro
Normal file
111
end_effectors/common/utils.xacro
Normal file
@@ -0,0 +1,111 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<!-- ============================================================== -->
|
||||
<!-- Macro to add an <inertial> tag based on yaml-load properties -->
|
||||
<!-- -->
|
||||
<!-- name: Name of the end_effector (without prefix) -->
|
||||
<!-- ee_inertials: Dictionary of inertia properties (see inertial.yaml) -->
|
||||
<!-- ============================================================== -->
|
||||
<xacro:macro name="ee-inertials" params="name ee_inertials:=^">
|
||||
<xacro:unless value="${name in ee_inertials}">${xacro.warning('No inertia properties defined for: ' + name)}</xacro:unless>
|
||||
<xacro:if value="${name in ee_inertials}">
|
||||
<!-- Access inertia properties of link 'name' -->
|
||||
<xacro:property name="link_inertials" value="${ee_inertials[name]}" lazy_eval="false" />
|
||||
<inertial>
|
||||
<origin rpy="${link_inertials.origin.rpy}" xyz="${link_inertials.origin.xyz}" />
|
||||
<mass value="${link_inertials.mass}" />
|
||||
<xacro:if value="${'inertia' in link_inertials}">
|
||||
<xacro:property name="I" value="${link_inertials.inertia}" />
|
||||
<inertia ixx="${I.xx}" ixy="${I.xy}" ixz="${I.xz}" iyy="${I.yy}" iyz="${I.yz}" izz="${I.zz}" />
|
||||
</xacro:if>
|
||||
</inertial>
|
||||
</xacro:if>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- ========================================================== -->
|
||||
<!-- Macro to add a single link, both with -->
|
||||
<!-- * detailed meshes for environmental collision checking -->
|
||||
<!-- * and coarse geometry models for self-collision checking -->
|
||||
<!-- (only if 'gazebo' param is set) -->
|
||||
<!-- -->
|
||||
<!-- name: Name of the end-effector (without prefix) -->
|
||||
<!-- rpy: Rotation of the *_sc link relative to parent [rad] -->
|
||||
<!-- self_collision_geometries: self <collision> models -->
|
||||
<!-- ========================================================== -->
|
||||
<xacro:macro name="ee_link_with_sc" params="name prefix=${ee_prefix} rpy:='0 0 0' **self_collision_geometries gazebo:=false with_sc:=false">
|
||||
<!-- sub-link defining detailed meshes for collision with environment -->
|
||||
<link name="${prefix}${name}">
|
||||
<visual name="${prefix}${name}_visual">
|
||||
<geometry>
|
||||
<mesh filename="package://${description_pkg}/meshes/robot_ee/${ee_id}/visual/${name}.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="${prefix}${name}_collision">
|
||||
<geometry>
|
||||
<mesh filename="package://franka_description/meshes/robot_ee/${ee_id}/collision/${name}.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:ee-inertials name="${name}" />
|
||||
</link>
|
||||
|
||||
<!-- sub-link defining coarse geometries of real end-effector's internal self-collision -->
|
||||
<xacro:if value="${with_sc}">
|
||||
<link name="${prefix}${name}_sc">
|
||||
<xacro:unless value="${gazebo}">
|
||||
<xacro:insert_block name="self_collision_geometries" />
|
||||
</xacro:unless>
|
||||
</link>
|
||||
<!-- fixed joint between both sub-links -->
|
||||
<joint name="${prefix}${name}_sc_joint" type="fixed">
|
||||
<origin rpy="${rpy}" />
|
||||
<parent link="${prefix}${name}" />
|
||||
<child link="${prefix}${name}_sc" />
|
||||
</joint>
|
||||
</xacro:if>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- =========================================================== -->
|
||||
<!-- Add a <collision> tag with a capsule, made from a cylinder -->
|
||||
<!-- with two spheres at its caps. The capsule will always be -->
|
||||
<!-- aligned with the axis of 'direction' you pass along. -->
|
||||
<!-- -->
|
||||
<!-- radius: Radii of both the cylinder and both spheres [m] -->
|
||||
<!-- length: Length of the cylinder/distance between the centers -->
|
||||
<!-- of the spheres. NOT overall length of capsule! -->
|
||||
<!-- xyz: Position of the center of the capsule/cylinder -->
|
||||
<!-- direction: One of { x, y, z, -x, -y, -z } -->
|
||||
<!-- =========================================================== -->
|
||||
<xacro:macro name="collision_capsule" params="radius length xyz:='0 0 0' direction:='z'">
|
||||
<xacro:property name="r" value="${pi/2.0 if 'y' in direction else 0}" />
|
||||
<xacro:property name="p" value="${pi/2.0 if 'x' in direction else 0}" />
|
||||
<xacro:property name="y" value="0" />
|
||||
<xacro:property name="x" value="${xyz.split(' ')[0]}" />
|
||||
<xacro:property name="y" value="${xyz.split(' ')[1]}" />
|
||||
<xacro:property name="z" value="${xyz.split(' ')[2]}" />
|
||||
<!-- Sphere center offsets from center of cylinder -->
|
||||
<xacro:property name="sx" value="${length / 2.0 if 'x' in direction else 0}" />
|
||||
<xacro:property name="sy" value="${length / 2.0 if 'y' in direction else 0}" />
|
||||
<xacro:property name="sz" value="${length / 2.0 if 'z' in direction else 0}" />
|
||||
|
||||
<collision>
|
||||
<origin xyz="${x} ${y} ${z}" rpy="${r} ${p} ${y}"/>
|
||||
<geometry>
|
||||
<cylinder radius="${radius}" length="${length}" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="${x+sx} ${y+sy} ${z+sz}" />
|
||||
<geometry>
|
||||
<sphere radius="${radius}" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="${x-sx} ${y-sy} ${z-sz}" />
|
||||
<geometry>
|
||||
<sphere radius="${radius}" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user