Skip to content
Snippets Groups Projects
Commit e5acbe38 authored by Johannes Mey's avatar Johannes Mey
Browse files

ROS distribution compatibility update

parent a6fde640
No related branches found
No related tags found
No related merge requests found
Showing
with 834 additions and 28 deletions
# generated from catkin/cmake/template/pkgConfig-version.cmake.in
set(PACKAGE_VERSION "0.8.2")
set(PACKAGE_VERSION_EXACT False)
set(PACKAGE_VERSION_COMPATIBLE False)
if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}")
set(PACKAGE_VERSION_EXACT True)
set(PACKAGE_VERSION_COMPATIBLE True)
endif()
if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}")
set(PACKAGE_VERSION_COMPATIBLE True)
endif()
# generated from catkin/cmake/template/pkgConfig.cmake.in
# append elements to a list and remove existing duplicates from the list
# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig
# self contained
macro(_list_append_deduplicate listname)
if(NOT "${ARGN}" STREQUAL "")
if(${listname})
list(REMOVE_ITEM ${listname} ${ARGN})
endif()
list(APPEND ${listname} ${ARGN})
endif()
endmacro()
# append elements to a list if they are not already in the list
# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig
# self contained
macro(_list_append_unique listname)
foreach(_item ${ARGN})
list(FIND ${listname} ${_item} _index)
if(_index EQUAL -1)
list(APPEND ${listname} ${_item})
endif()
endforeach()
endmacro()
# pack a list of libraries with optional build configuration keywords
# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig
# self contained
macro(_pack_libraries_with_build_configuration VAR)
set(${VAR} "")
set(_argn ${ARGN})
list(LENGTH _argn _count)
set(_index 0)
while(${_index} LESS ${_count})
list(GET _argn ${_index} lib)
if("${lib}" MATCHES "^(debug|optimized|general)$")
math(EXPR _index "${_index} + 1")
if(${_index} EQUAL ${_count})
message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library")
endif()
list(GET _argn ${_index} library)
list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}")
else()
list(APPEND ${VAR} "${lib}")
endif()
math(EXPR _index "${_index} + 1")
endwhile()
endmacro()
# unpack a list of libraries with optional build configuration keyword prefixes
# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig
# self contained
macro(_unpack_libraries_with_build_configuration VAR)
set(${VAR} "")
foreach(lib ${ARGN})
string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}")
list(APPEND ${VAR} "${lib}")
endforeach()
endmacro()
if(franka_description_CONFIG_INCLUDED)
return()
endif()
set(franka_description_CONFIG_INCLUDED TRUE)
# set variables for source/devel/install prefixes
if("FALSE" STREQUAL "TRUE")
set(franka_description_SOURCE_PREFIX /tmp/binarydeb/ros-noetic-franka-description-0.8.2)
set(franka_description_DEVEL_PREFIX /tmp/binarydeb/ros-noetic-franka-description-0.8.2/obj-x86_64-linux-gnu/devel)
set(franka_description_INSTALL_PREFIX "")
set(franka_description_PREFIX ${franka_description_DEVEL_PREFIX})
else()
set(franka_description_SOURCE_PREFIX "")
set(franka_description_DEVEL_PREFIX "")
set(franka_description_INSTALL_PREFIX /opt/ros/noetic)
set(franka_description_PREFIX ${franka_description_INSTALL_PREFIX})
endif()
# warn when using a deprecated package
if(NOT "" STREQUAL "")
set(_msg "WARNING: package 'franka_description' is deprecated")
# append custom deprecation text if available
if(NOT "" STREQUAL "TRUE")
set(_msg "${_msg} ()")
endif()
message("${_msg}")
endif()
# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project
set(franka_description_FOUND_CATKIN_PROJECT TRUE)
if(NOT " " STREQUAL " ")
set(franka_description_INCLUDE_DIRS "")
set(_include_dirs "")
if(NOT "https://github.com/frankaemika/franka_ros/issues " STREQUAL " ")
set(_report "Check the issue tracker 'https://github.com/frankaemika/franka_ros/issues' and consider creating a ticket if the problem has not been reported yet.")
elseif(NOT "http://wiki.ros.org/franka_description " STREQUAL " ")
set(_report "Check the website 'http://wiki.ros.org/franka_description' for information and consider reporting the problem.")
else()
set(_report "Report the problem to the maintainer 'Franka Emika GmbH <support@franka.de>' and request to fix the problem.")
endif()
foreach(idir ${_include_dirs})
if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir})
set(include ${idir})
elseif("${idir} " STREQUAL "include ")
get_filename_component(include "${franka_description_DIR}/../../../include" ABSOLUTE)
if(NOT IS_DIRECTORY ${include})
message(FATAL_ERROR "Project 'franka_description' specifies '${idir}' as an include dir, which is not found. It does not exist in '${include}'. ${_report}")
endif()
else()
message(FATAL_ERROR "Project 'franka_description' specifies '${idir}' as an include dir, which is not found. It does neither exist as an absolute directory nor in '\${prefix}/${idir}'. ${_report}")
endif()
_list_append_unique(franka_description_INCLUDE_DIRS ${include})
endforeach()
endif()
set(libraries "")
foreach(library ${libraries})
# keep build configuration keywords, target names and absolute libraries as-is
if("${library}" MATCHES "^(debug|optimized|general)$")
list(APPEND franka_description_LIBRARIES ${library})
elseif(${library} MATCHES "^-l")
list(APPEND franka_description_LIBRARIES ${library})
elseif(${library} MATCHES "^-")
# This is a linker flag/option (like -pthread)
# There's no standard variable for these, so create an interface library to hold it
if(NOT franka_description_NUM_DUMMY_TARGETS)
set(franka_description_NUM_DUMMY_TARGETS 0)
endif()
# Make sure the target name is unique
set(interface_target_name "catkin::franka_description::wrapped-linker-option${franka_description_NUM_DUMMY_TARGETS}")
while(TARGET "${interface_target_name}")
math(EXPR franka_description_NUM_DUMMY_TARGETS "${franka_description_NUM_DUMMY_TARGETS}+1")
set(interface_target_name "catkin::franka_description::wrapped-linker-option${franka_description_NUM_DUMMY_TARGETS}")
endwhile()
add_library("${interface_target_name}" INTERFACE IMPORTED)
if("${CMAKE_VERSION}" VERSION_LESS "3.13.0")
set_property(
TARGET
"${interface_target_name}"
APPEND PROPERTY
INTERFACE_LINK_LIBRARIES "${library}")
else()
target_link_options("${interface_target_name}" INTERFACE "${library}")
endif()
list(APPEND franka_description_LIBRARIES "${interface_target_name}")
elseif(TARGET ${library})
list(APPEND franka_description_LIBRARIES ${library})
elseif(IS_ABSOLUTE ${library})
list(APPEND franka_description_LIBRARIES ${library})
else()
set(lib_path "")
set(lib "${library}-NOTFOUND")
# since the path where the library is found is returned we have to iterate over the paths manually
foreach(path /opt/ros/noetic/lib;/opt/ros/noetic/lib)
find_library(lib ${library}
PATHS ${path}
NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)
if(lib)
set(lib_path ${path})
break()
endif()
endforeach()
if(lib)
_list_append_unique(franka_description_LIBRARY_DIRS ${lib_path})
list(APPEND franka_description_LIBRARIES ${lib})
else()
# as a fall back for non-catkin libraries try to search globally
find_library(lib ${library})
if(NOT lib)
message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'. The library is neither a target nor built/installed properly. Did you compile project 'franka_description'? Did you find_package() it before the subdirectory containing its code is included?")
endif()
list(APPEND franka_description_LIBRARIES ${lib})
endif()
endif()
endforeach()
set(franka_description_EXPORTED_TARGETS "")
# create dummy targets for exported code generation targets to make life of users easier
foreach(t ${franka_description_EXPORTED_TARGETS})
if(NOT TARGET ${t})
add_custom_target(${t})
endif()
endforeach()
set(depends "xacro")
foreach(depend ${depends})
string(REPLACE " " ";" depend_list ${depend})
# the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls
list(GET depend_list 0 franka_description_dep)
list(LENGTH depend_list count)
if(${count} EQUAL 1)
# simple dependencies must only be find_package()-ed once
if(NOT ${franka_description_dep}_FOUND)
find_package(${franka_description_dep} REQUIRED NO_MODULE)
endif()
else()
# dependencies with components must be find_package()-ed again
list(REMOVE_AT depend_list 0)
find_package(${franka_description_dep} REQUIRED NO_MODULE ${depend_list})
endif()
_list_append_unique(franka_description_INCLUDE_DIRS ${${franka_description_dep}_INCLUDE_DIRS})
# merge build configuration keywords with library names to correctly deduplicate
_pack_libraries_with_build_configuration(franka_description_LIBRARIES ${franka_description_LIBRARIES})
_pack_libraries_with_build_configuration(_libraries ${${franka_description_dep}_LIBRARIES})
_list_append_deduplicate(franka_description_LIBRARIES ${_libraries})
# undo build configuration keyword merging after deduplication
_unpack_libraries_with_build_configuration(franka_description_LIBRARIES ${franka_description_LIBRARIES})
_list_append_unique(franka_description_LIBRARY_DIRS ${${franka_description_dep}_LIBRARY_DIRS})
_list_append_deduplicate(franka_description_EXPORTED_TARGETS ${${franka_description_dep}_EXPORTED_TARGETS})
endforeach()
set(pkg_cfg_extras "")
foreach(extra ${pkg_cfg_extras})
if(NOT IS_ABSOLUTE ${extra})
set(extra ${franka_description_DIR}/${extra})
endif()
include(${extra})
endforeach()
File added
File added
File added
File added
File added
File added
File added
File added
File added
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="2"> <package format="2">
<name>franka_description</name> <name>franka_description</name>
<version>0.7.0</version> <version>0.8.2</version>
<description>franka_description contains URDF files and meshes of Franka Emika robots</description> <description>franka_description contains URDF files and meshes of Franka Emika robots</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer> <maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license> <license>Apache 2.0</license>
......
...@@ -27,10 +27,10 @@ ...@@ -27,10 +27,10 @@
<!-- right arm with gripper --> <!-- right arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_1)" connected_to="base" xyz="0 -0.5 1" safety_distance="0.03"/> <xacro:panda_arm arm_id="$(arg arm_id_1)" connected_to="base" xyz="0 -0.5 1" safety_distance="0.03"/>
<xacro:hand ns="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" safety_distance="0.03"/> <xacro:hand arm_id="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" safety_distance="0.03"/>
<!-- left arm with gripper --> <!-- left arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_2)" connected_to="base" xyz="0 0.5 1" safety_distance="0.03"/> <xacro:panda_arm arm_id="$(arg arm_id_2)" connected_to="base" xyz="0 0.5 1" safety_distance="0.03"/>
<xacro:hand ns="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8" safety_distance="0.03"/> <xacro:hand arm_id="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8" safety_distance="0.03"/>
</robot> </robot>
<?xml version="1.0" encoding="utf-8"?> <?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<xacro:include filename="hand.xacro"/> <xacro:include filename="hand.xacro"/>
<xacro:hand ns="panda" safety_distance="0.03"/> <xacro:hand arm_id="panda" safety_distance="0.03"/>
</robot> </robot>
<?xml version="1.0" encoding="utf-8"?> <?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand"> <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 --> <!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0"> <xacro:macro name="hand" params="connected_to:='' arm_id:='panda' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0">
<xacro:unless value="${connected_to == ''}"> <xacro:unless value="${connected_to == ''}">
<joint name="${ns}_hand_joint" type="fixed"> <joint name="${arm_id}_hand_joint" type="fixed">
<parent link="${connected_to}"/> <parent link="${connected_to}"/>
<child link="${ns}_hand"/> <child link="${arm_id}_hand"/>
<origin xyz="${xyz}" rpy="${rpy}"/> <origin xyz="${xyz}" rpy="${rpy}"/>
</joint> </joint>
</xacro:unless> </xacro:unless>
<link name="${ns}_hand"> <link name="${arm_id}_hand">
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://franka_description/meshes/visual/hand.dae"/> <mesh filename="package://franka_description/meshes/visual/hand.dae"/>
...@@ -52,14 +52,21 @@ ...@@ -52,14 +52,21 @@
</geometry> </geometry>
</collision> </collision>
</link> </link>
<link name="${ns}_leftfinger"> <!-- Define the hand_tcp frame -->
<link name="${arm_id}_hand_tcp" />
<joint name="${arm_id}_hand_tcp_joint" type="fixed">
<origin xyz="0 0 0.1034" rpy="0 0 0" />
<parent link="${arm_id}_hand" />
<child link="${arm_id}_hand_tcp" />
</joint>
<link name="${arm_id}_leftfinger">
<visual> <visual>
<geometry> <geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/> <mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry> </geometry>
</visual> </visual>
</link> </link>
<link name="${ns}_rightfinger"> <link name="${arm_id}_rightfinger">
<visual> <visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/> <origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry> <geometry>
...@@ -67,20 +74,20 @@ ...@@ -67,20 +74,20 @@
</geometry> </geometry>
</visual> </visual>
</link> </link>
<joint name="${ns}_finger_joint1" type="prismatic"> <joint name="${arm_id}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/> <parent link="${arm_id}_hand"/>
<child link="${ns}_leftfinger"/> <child link="${arm_id}_leftfinger"/>
<origin xyz="0 0 0.0584" rpy="0 0 0"/> <origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/> <limit effort="100" lower="0.0" upper="0.04" velocity="0.2"/>
</joint> </joint>
<joint name="${ns}_finger_joint2" type="prismatic"> <joint name="${arm_id}_finger_joint2" type="prismatic">
<parent link="${ns}_hand"/> <parent link="${arm_id}_hand"/>
<child link="${ns}_rightfinger"/> <child link="${arm_id}_rightfinger"/>
<origin xyz="0 0 0.0584" rpy="0 0 0"/> <origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 -1 0"/> <axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/> <limit effort="100" lower="0.0" upper="0.04" velocity="0.2"/>
<mimic joint="${ns}_finger_joint1" /> <mimic joint="${arm_id}_finger_joint1" />
</joint> </joint>
</xacro:macro> </xacro:macro>
</robot> </robot>
<?xml version='1.0' encoding='utf-8'?> <?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<!-- Name of this panda -->
<xacro:arg name="arm_id" default="panda" />
<!-- Should a franka_gripper be mounted at the flange?" -->
<xacro:arg name="hand" default="false" />
<!-- Is the robot being simulated in gazebo?" -->
<xacro:arg name="gazebo" default="false" />
<xacro:unless value="$(arg gazebo)">
<!-- Create a URDF for a real hardware -->
<xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" /> <xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" />
<xacro:panda_arm safety_distance="0.03"/> <xacro:panda_arm arm_id="$(arg arm_id)" safety_distance="0.03"/>
<xacro:if value="$(arg hand)">
<xacro:include filename="$(find franka_description)/robots/hand.xacro"/>
<xacro:hand arm_id="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" safety_distance="0.03"/>
</xacro:if>
</xacro:unless>
<xacro:if value="$(arg gazebo)">
<xacro:arg name="xyz" default="0 0 0" />
<xacro:arg name="rpy" default="0 0 0" />
<!-- Create a simulatable URDF -->
<xacro:include filename="$(find franka_description)/robots/utils.xacro" />
<xacro:include filename="$(find franka_description)/robots/panda_gazebo.xacro" />
<xacro:panda_arm arm_id="$(arg arm_id)" />
<xacro:if value="$(arg hand)">
<xacro:hand arm_id="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" />
<xacro:gazebo-joint joint="$(arg arm_id)_finger_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_finger_joint2" transmission="hardware_interface/EffortJointInterface" />
</xacro:if>
<!-- Gazebo requires a joint to a link called "world" for statically mounted robots -->
<link name="world" />
<joint name="world_joint" type="fixed">
<origin xyz="$(arg xyz)" rpy="$(arg rpy)" />
<parent link="world" />
<child link="$(arg arm_id)_link0" />
</joint>
<xacro:gazebo-joint joint="$(arg arm_id)_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint2" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint3" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint4" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint5" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint6" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint7" transmission="hardware_interface/EffortJointInterface" />
<xacro:transmission-franka-state arm_id="$(arg arm_id)" />
<xacro:transmission-franka-model arm_id="$(arg arm_id)"
root="$(arg arm_id)_joint1"
tip="$(arg arm_id)_joint8"
/>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<controlPeriod>0.001</controlPeriod>
<robotSimType>franka_gazebo/FrankaHWSim</robotSimType>
</plugin>
<self_collide>true</self_collide>
</gazebo>
</xacro:if>
</robot> </robot>
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find franka_description)/robots/panda_arm.xacro"/>
<xacro:include filename="$(find franka_description)/robots/hand.xacro"/>
<xacro:panda_arm safety_distance="0.03"/>
<xacro:hand ns="panda" rpy="0 0 ${-pi/4}" connected_to="panda_link8" safety_distance="0.03"/>
</robot>
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<!-- =============================================================== -->
<!-- || This file does not contain official inertial properties || -->
<!-- || of panda robot. The values are from the identification || -->
<!-- || results published in: Identification of the Franka Emika || -->
<!-- || PandaRobot With Retrieval of Feasible Parameters Using || -->
<!-- || Penalty-Based Optimization || -->
<!-- || by: Claudio Gaz, Marco Cognetti, Alexander Oliva, || -->
<!-- || Paolo Robuffo Giordano, Alessandro de Luca || -->
<!-- =============================================================== -->
<xacro:macro name="panda_arm" params="arm_id:='panda' connected_to:='' xyz:='0 0 0' rpy:='0 0 0'">
<xacro:unless value="${not connected_to}">
<joint name="${arm_id}_joint_${connected_to}" type="fixed">
<parent link="${connected_to}"/>
<child link="${arm_id}_link0"/>
<origin rpy="${rpy}" xyz="${xyz}"/>
</joint>
</xacro:unless>
<link name="${arm_id}_link0">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link0.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link0.stl"/>
</geometry>
</collision>
<inertial>
<!-- Estimated guesses from CAD -->
<origin rpy="0 0 0" xyz="-0.041018 -0.00014 0.049974"/>
<mass value="0.629769"/>
<inertia ixx="0.00315" ixy="8.2904E-07" ixz="0.00015"
iyy="0.00388" iyz="8.2299E-06"
izz="0.004285" />
</inertial>
</link>
<link name="${arm_id}_link1">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link1.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.003875 0.002081 -0.04762"/>
<mass value="4.970684"/>
<inertia ixx="0.70337" ixy="-0.00013900" ixz="0.0067720"
iyy="0.70661" iyz="0.019169"
izz="0.0091170" />
</inertial>
</link>
<joint name="${arm_id}_joint1" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="0 0 0" xyz="0 0 0.333"/>
<parent link="${arm_id}_link0"/>
<child link="${arm_id}_link1"/>
<axis xyz="0 0 1"/>
<limit acceleration="15" lower="-2.9671" effort="87" upper="2.9671" velocity="2.5"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link2">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link2.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz=" -0.003141 -0.02872 0.003495"/>
<mass value="0.646926"/>
<inertia ixx="0.0079620" ixy="-3.9250e-3" ixz="1.0254e-02"
iyy="2.8110e-02" iyz="7.0400e-04"
izz="2.5995e-02" />
</inertial>
</link>
<joint name="${arm_id}_joint2" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/>
<origin rpy="${-pi/2} 0 0" xyz="0 0 0"/>
<parent link="${arm_id}_link1"/>
<child link="${arm_id}_link2"/>
<axis xyz="0 0 1"/>
<limit acceleration="7.5" lower="-1.8326" effort="87" upper="1.8326" velocity="2.5"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link3">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link3.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="2.7518e-02 3.9252e-02 -6.6502e-02"/>
<mass value="3.228604"/>
<inertia ixx="3.7242e-02" ixy="-4.7610e-03" ixz="-1.1396e-02"
iyy="3.6155e-02" iyz="-1.2805e-02"
izz="1.0830e-02" />
</inertial>
</link>
<joint name="${arm_id}_joint3" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="${pi/2} 0 0" xyz="0 -0.316 0"/>
<parent link="${arm_id}_link2"/>
<child link="${arm_id}_link3"/>
<axis xyz="0 0 1"/>
<limit acceleration="12.5" lower="-2.9671" effort="87" upper="2.9671" velocity="2.5"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link4">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link4.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link4.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-5.317e-02 1.04419e-01 2.7454e-02"/>
<mass value="3.587895"/>
<inertia ixx="2.5853e-02" ixy="7.7960e-03" ixz="-1.3320e-03"
iyy="1.9552e-02" iyz="8.6410e-03"
izz="2.8323e-02" />
</inertial>
</link>
<joint name="${arm_id}_joint4" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
<origin rpy="${pi/2} 0 0" xyz="0.0825 0 0"/>
<parent link="${arm_id}_link3"/>
<child link="${arm_id}_link4"/>
<axis xyz="0 0 1"/>
<limit acceleration="12.5" lower="-3.1416" effort="87" upper="-0.4" velocity="2.5"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link5">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link5.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link5.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-1.1953e-02 4.1065e-02 -3.8437e-02"/>
<mass value="1.225946"/>
<inertia ixx="3.5549e-02" ixy="-2.1170e-03" ixz="-4.0370e-03"
iyy="2.9474e-02" iyz="2.2900e-04"
izz="8.6270e-03" />
</inertial>
</link>
<joint name="${arm_id}_joint5" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="${-pi/2} 0 0" xyz="-0.0825 0.384 0"/>
<parent link="${arm_id}_link4"/>
<child link="${arm_id}_link5"/>
<axis xyz="0 0 1"/>
<limit acceleration="15" lower="-2.9671" effort="12" upper="2.9671" velocity="3"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link6">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link6.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link6.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="6.0149e-02 -1.4117e-02 -1.0517e-02"/>
<mass value="1.666555"/>
<inertia ixx="1.9640e-03" ixy="1.0900e-04" ixz="-1.1580e-03"
iyy="4.3540e-03" iyz="3.4100e-04"
izz="5.4330e-03" />
</inertial>
</link>
<joint name="${arm_id}_joint6" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/>
<origin rpy="${pi/2} 0 0" xyz="0 0 0"/>
<parent link="${arm_id}_link5"/>
<child link="${arm_id}_link6"/>
<axis xyz="0 0 1"/>
<limit acceleration="20" lower="-0.0873" effort="12" upper="3.8223" velocity="3"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link7">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link7.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link7.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="1.0517e-02 -4.252e-03 6.1597e-02"/>
<mass value="7.35522e-01"/>
<inertia ixx="1.2516e-02" ixy="-4.2800e-04" ixz="-1.1960e-03"
iyy="1.0027e-02" iyz="-7.4100e-04"
izz="4.8150e-03"/>
</inertial>
</link>
<joint name="${arm_id}_joint7" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
<origin rpy="${pi/2} 0 0" xyz="0.088 0 0"/>
<parent link="${arm_id}_link6"/>
<child link="${arm_id}_link7"/>
<axis xyz="0 0 1"/>
<limit acceleration="20" lower="-2.9671" effort="12" upper="2.9671" velocity="3"/>
<dynamics D="1" K="7000" mu_coulomb="0" mu_viscous="16" damping="0.003" friction="0.0"/>
</joint>
<link name="${arm_id}_link8" />
<joint name="${arm_id}_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107"/>
<parent link="${arm_id}_link7"/>
<child link="${arm_id}_link8"/>
<axis xyz="0 0 0"/>
</joint>
</xacro:macro>
<xacro:macro name="hand" params="connected_to:='' arm_id:='' xyz:='0 0 0' rpy:='0 0 0'">
<xacro:include filename="$(find franka_description)/robots/utils.xacro"/>
<xacro:unless value="${connected_to == ''}">
<joint name="${arm_id}_hand_joint" type="fixed">
<parent link="${connected_to}"/>
<child link="${arm_id}_hand"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:unless>
<link name="${arm_id}_hand">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/hand.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://franka_description/meshes/collision/hand.stl" />
</geometry>
</collision>
<inertial>
<mass value="0.73" />
<origin xyz="-0.01 0 0.03" />
<inertia ixx="0.001" ixy="0" ixz="0"
iyy="0.0025" iyz="0"
izz="0.0017" />
</inertial>
</link>
<xacro:macro name="finger-collision" params="sign">
<!-- screw mount -->
<collision>
<origin xyz="0 ${sign}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 ${sign}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 ${sign}15.9e-3 28.35e-3" rpy="${sign}${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 ${sign}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:macro>
<link name="${arm_id}_leftfinger">
<xacro:inertia-cylinder mass="15e-3" radius="0.01" h="0.04"/>
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<xacro:finger-collision sign="+" />
</link>
<link name="${arm_id}_rightfinger">
<xacro:inertia-cylinder mass="15e-3" radius="0.01" h="0.04"/>
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<xacro:finger-collision sign="-" />
</link>
<!-- Friction specific material for Rubber/Rubber contact -->
<!-- See: -->
<xacro:gazebo-friction link="${arm_id}_leftfinger" mu="1.13" />
<xacro:gazebo-friction link="${arm_id}_rightfinger" mu="1.13" />
<joint name="${arm_id}_finger_joint1" type="prismatic">
<parent link="${arm_id}_hand"/>
<child link="${arm_id}_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 friction="0.0" damping="0.03"/>
</joint>
<joint name="${arm_id}_finger_joint2" type="prismatic">
<parent link="${arm_id}_hand"/>
<child link="${arm_id}_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"/>
<dynamics friction="0.0" damping="0.03"/>
<mimic joint="${arm_id}_finger_joint1" />
</joint>
</xacro:macro>
</robot>
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- ========================================================== -->
<!-- Adds the required tags to simulate one joint in gazebo -->
<!-- -->
<!-- joint - Name of the panda joint to simulate -->
<!-- transmission - type of the transmission of the joint -->
<!-- ========================================================== -->
<xacro:macro name="gazebo-joint" params="joint transmission:=hardware_interface/EffortJointInterface">
<gazebo reference="${joint}">
<!-- Needed for ODE to output external wrenches on joints -->
<provideFeedback>true</provideFeedback>
</gazebo>
<transmission name="${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
<hardwareInterface>${transmission}</hardwareInterface>
</joint>
<actuator name="${joint}_motor">
<hardwareInterface>${transmission}</hardwareInterface>
</actuator>
</transmission>
</xacro:macro>
<xacro:macro name="gazebo-friction" params="link mu">
<gazebo reference="${link}">
<collision>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode>
<!-- These two parameter need application specific tuning. -->
<!-- Usually you want no "snap out" velocity and a generous -->
<!-- penetration depth to keep the grasping stable -->
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode>
<mu>${mu}</mu>
<mu2>${mu}</mu2>
</ode>
</friction>
<bounce/>
</surface>
</collision>
</gazebo>
</xacro:macro>
<!-- ========================================================== -->
<!-- Adds the required tags to provide a `FrankaStateInterface` -->
<!-- when simulating with franka_hw_sim plugin -->
<!-- -->
<!-- arm_id - Arm ID of the panda to simulate (default 'panda') -->
<!-- ========================================================== -->
<xacro:macro name="transmission-franka-state" params="arm_id:=panda">
<transmission name="${arm_id}_franka_state">
<type>franka_hw/FrankaStateInterface</type>
<joint name="${arm_id}_joint1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<actuator name="${arm_id}_motor1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
</transmission>
</xacro:macro>
<!-- ============================================================ -->
<!-- Adds the required tags to provide a `FrankaModelInterface` -->
<!-- when simulating with franka_hw_sim plugin -->
<!-- -->
<!-- arm_id - Arm ID of the panda to simulate (default 'panda') -->
<!-- root - Joint name of the base of the robot -->
<!-- tip - Joint name of the tip of the robot (flange or hand) -->
<!-- ============================================================ -->
<xacro:macro name="transmission-franka-model" params="arm_id:=panda root:=panda_joint1 tip:=panda_joint7">
<transmission name="${arm_id}_franka_model">
<type>franka_hw/FrankaModelInterface</type>
<joint name="${root}">
<role>root</role>
<hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
</joint>
<joint name="${tip}">
<role>tip</role>
<hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
</joint>
<actuator name="${root}_motor_root"><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
<actuator name="${tip}_motor_tip" ><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
</transmission>
</xacro:macro>
<xacro:macro name="inertia-cylinder" params="mass radius h">
<inertial>
<mass value="${mass}" />
<inertia ixx="${1./12 * mass * (3 * radius**2 + h**2)}" ixy = "0" ixz = "0"
iyy="${1./12 * mass * (3 * radius**2 + h**2)}" iyz = "0"
izz="${1./2 * mass * radius**2}" />
</inertial>
</xacro:macro>
</robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment