Skip to content

Commit

Permalink
More updates.
Browse files Browse the repository at this point in the history
This includes some example launch files.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Jan 22, 2020
1 parent 86f2be5 commit 4b2f66d
Show file tree
Hide file tree
Showing 16 changed files with 524 additions and 9 deletions.
14 changes: 7 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(kdl_parser REQUIRED)
find_package(orocos_kdl REQUIRED)
Expand All @@ -28,6 +29,7 @@ add_library(
${PROJECT_NAME} SHARED
src/robot_state_publisher.cpp)
ament_target_dependencies(${PROJECT_NAME}
builtin_interfaces
geometry_msgs
kdl_parser
orocos_kdl
Expand All @@ -46,13 +48,7 @@ add_executable(
${PROJECT_NAME}_node
src/robot_state_publisher_node.cpp)
ament_target_dependencies(${PROJECT_NAME}_node
kdl_parser
orocos_kdl
rclcpp
sensor_msgs
std_msgs
tf2_ros
urdf
)
target_link_libraries(${PROJECT_NAME}_node
${PROJECT_NAME}
Expand All @@ -74,6 +70,10 @@ install(
DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY launch urdf
DESTINATION share/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_cmake_cppcheck REQUIRED)
find_package(ament_cmake_cpplint REQUIRED)
Expand All @@ -84,7 +84,7 @@ if(BUILD_TESTING)
ament_uncrustify()
endif()

ament_export_dependencies(orocos_kdl rclcpp sensor_msgs std_msgs tf2_ros urdf)
ament_export_dependencies(builtin_interfaces orocos_kdl rclcpp sensor_msgs std_msgs tf2_ros urdf)
ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})
ament_package()
6 changes: 4 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,15 @@ Robot State Publisher

This package contains the Robot State Publisher, a node and a class to publish the state of a robot to tf2. Once the state gets published, it is available to all components in the system that also use tf2. The package takes the joint angles of the robot as input and publishes the 3D poses of the robot links, using a kinematic tree model of the robot.

Examples showing how to pass the `robot_description` parameter using a launch file are available in the 'launch' subdirectory.

Published Topics
----------------
* `robot_description` (`std_msgs/String`) - The description of the robot URDF as a string. Republishes the value set in the `robot_description` parameter, which is useful for getting informed of dynamic changes to the URDF. Published using the "transient local" quality of service, so subscribers should also be "transient local".
* `robot_description` (`std_msgs/msg/String`) - The description of the robot URDF as a string. Republishes the value set in the `robot_description` parameter, which is useful for getting informed of dynamic changes to the URDF. Published using the "transient local" quality of service, so subscribers should also be "transient local".

Subscribed Topics
-----------------
* `joint_states` (`sensor_msgs/JointState`) - The joint state updates to the robot poses. The RobotStatePublisher class takes these updates, does transformations (such as mimic joints), and then publishes the results on the tf2 topics.
* `joint_states` (`sensor_msgs/msg/JointState`) - The joint state updates to the robot poses. The RobotStatePublisher class takes these updates, does transformations (such as mimic joints), and then publishes the results on the tf2 topics.

Parameters
----------
Expand Down
1 change: 1 addition & 0 deletions include/robot_state_publisher/robot_state_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#ifndef ROBOT_STATE_PUBLISHER__ROBOT_STATE_PUBLISHER_HPP_
#define ROBOT_STATE_PUBLISHER__ROBOT_STATE_PUBLISHER_HPP_

#include <builtin_interfaces/msg/time.hpp>
#include <kdl/tree.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
Expand Down
43 changes: 43 additions & 0 deletions launch/rsp-launch-urdf-file.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<!--
Copyright (c) 2020 Open Source Robotics Foundation, Inc.
All rights reserved.
Software License Agreement (BSD License 2.0)
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above
copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided
with the distribution.
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
-->

<!--
This launch file shows how to launch robot_state_publisher with a simple
URDF read from a file (found using the find-pkg-share substitution).
-->
<launch>
<node pkg="robot_state_publisher" exec="robot_state_publisher_node">
<param name='robot_description' value="$(command 'cat $(find-pkg-share robot_state_publisher)/urdf/test-desc.urdf')"/>
</node>
</launch>
56 changes: 56 additions & 0 deletions launch/rsp-launch-urdf-file1.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# Copyright (c) 2020 Open Source Robotics Foundation, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

# This launch file shows how to launch robot_state_publisher with a simple
# URDF read from a file (found using FindPackageShare) and passed as the
# 'robot_description' parameter.

import os

import launch
import launch_ros.actions
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
urdf_dir = os.path.join(FindPackageShare('robot_state_publisher').find('robot_state_publisher'), 'urdf')
urdf_file = os.path.join(urdf_dir, 'test-desc.urdf')
with open(urdf_file, 'r') as infp:
robot_desc = infp.read()

params = {'robot_description': robot_desc}
rsp = launch_ros.actions.Node(package='robot_state_publisher',
node_executable='robot_state_publisher_node',
output='both',
parameters=[params])

return launch.LaunchDescription([rsp])
57 changes: 57 additions & 0 deletions launch/rsp-launch-urdf-file2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
# Copyright (c) 2020 Open Source Robotics Foundation, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

# This launch file shows how to launch robot_state_publisher with a simple
# URDF read from a file (found using ament_get_package_share_directory) and
# passed as the 'robot_description' parameter.

import os

from ament_index_python.packages import get_package_share_directory

import launch
import launch_ros.actions


def generate_launch_description():
urdf_dir = os.path.join(get_package_share_directory('robot_state_publisher'), 'urdf')
urdf_file = os.path.join(urdf_dir, 'test-desc.urdf')
with open(urdf_file, 'r') as infp:
robot_desc = infp.read()

params = {'robot_description': robot_desc}
rsp = launch_ros.actions.Node(package='robot_state_publisher',
node_executable='robot_state_publisher_node',
output='both',
parameters=[params])

return launch.LaunchDescription([rsp])
60 changes: 60 additions & 0 deletions launch/rsp-launch-urdf-inline.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# Copyright (c) 2020 Open Source Robotics Foundation, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

# This launch file shows how to launch robot_state_publisher with a
# simple URDF passed as the 'robot_description' parameter.

import launch
import launch_ros.actions


def generate_launch_description():
robot_desc = """\
<?xml version="1.0"?>
<robot name="test">
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.6" radius="0.2"/>
</geometry>
<material name="blue"/>
</visual>
</link>
</robot>"""

params = {'robot_description': robot_desc}
rsp = launch_ros.actions.Node(package='robot_state_publisher',
node_executable='robot_state_publisher_node',
output='both',
parameters=[params])

return launch.LaunchDescription([rsp])
56 changes: 56 additions & 0 deletions launch/rsp-launch-urdf-inline.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
<!--
Copyright (c) 2020 Open Source Robotics Foundation, Inc.
All rights reserved.
Software License Agreement (BSD License 2.0)
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above
copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided
with the distribution.
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
-->

<!--
This launch file shows how to launch robot_state_publisher with a simple
URDF passed as the 'robot_description' parameter.
-->

<launch>
<node pkg="robot_state_publisher" exec="robot_state_publisher_node">
<param name='robot_description' value="
&lt;?xml version='1.0'?&gt;
&lt;robot name='test'&gt;
&lt;link name='base_link'&gt;
&lt;visual&gt;
&lt;geometry&gt;
&lt;cylinder length='0.6' radius='0.2'/&gt;
&lt;/geometry&gt;
&lt;material name='blue'/&gt;
&lt;/visual&gt;
&lt;/link&gt;
&lt;/robot&gt;
"/>
</node>
</launch>
Loading

0 comments on commit 4b2f66d

Please sign in to comment.