From 65dd3dc58df9aa85ed9e6d6e33afdd04832c9161 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 13 Nov 2024 15:45:05 +0100 Subject: [PATCH] Refactor tf_bridge demo. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- ros_gz_sim_demos/CMakeLists.txt | 6 ++ ros_gz_sim_demos/README.md | 2 +- ros_gz_sim_demos/config/tf_bridge.yaml | 18 ++++++ ros_gz_sim_demos/launch/tf_bridge.launch.py | 59 -------------------- ros_gz_sim_demos/launch/tf_bridge.launch.xml | 6 ++ 5 files changed, 31 insertions(+), 60 deletions(-) create mode 100644 ros_gz_sim_demos/config/tf_bridge.yaml delete mode 100644 ros_gz_sim_demos/launch/tf_bridge.launch.py create mode 100644 ros_gz_sim_demos/launch/tf_bridge.launch.xml diff --git a/ros_gz_sim_demos/CMakeLists.txt b/ros_gz_sim_demos/CMakeLists.txt index 8e0f580a..9b69104b 100644 --- a/ros_gz_sim_demos/CMakeLists.txt +++ b/ros_gz_sim_demos/CMakeLists.txt @@ -9,6 +9,12 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() +install( + DIRECTORY + config/ + DESTINATION share/${PROJECT_NAME}/config +) + install( DIRECTORY launch/ diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index c404a4dc..3d46dcf2 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -203,6 +203,6 @@ and transforms of a robot in rviz. To try the demo launch: - ros2 launch ros_gz_sim_demos tf_bridge.launch.py + ros2 launch ros_gz_sim_demos tf_bridge.launch.xml ![](images/tf_bridge.gif) diff --git a/ros_gz_sim_demos/config/tf_bridge.yaml b/ros_gz_sim_demos/config/tf_bridge.yaml new file mode 100644 index 00000000..a1bec54e --- /dev/null +++ b/ros_gz_sim_demos/config/tf_bridge.yaml @@ -0,0 +1,18 @@ +# tf_bridge configuration. +- ros_topic_name: "/joint_states" + gz_topic_name: "/world/default/model/double_pendulum_with_base0/joint_state" + ros_type_name: "sensor_msgs/msg/JointState" + gz_type_name: "gz.msgs.Model" + subscriber_queue: 5 + publisher_queue: 6 + lazy: false + direction: GZ_TO_ROS + +- ros_topic_name: "/tf" + gz_topic_name: "/model/double_pendulum_with_base0/pose" + ros_type_name: "tf2_msgs/msg/TFMessage" + gz_type_name: "gz.msgs.Pose_V" + subscriber_queue: 5 + publisher_queue: 6 + lazy: false + direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/tf_bridge.launch.py b/ros_gz_sim_demos/launch/tf_bridge.launch.py deleted file mode 100644 index 42f76cdc..00000000 --- a/ros_gz_sim_demos/launch/tf_bridge.launch.py +++ /dev/null @@ -1,59 +0,0 @@ -# Copyright 2022 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory - -from launch import LaunchDescription -from launch.actions import ExecuteProcess -from launch_ros.actions import Node - - -def generate_launch_description(): - pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - return LaunchDescription([ - # Launch gazebo - ExecuteProcess( - cmd=[ - 'gz', 'sim', '-r', - os.path.join( - pkg_ros_gz_sim_demos, - 'models', - 'double_pendulum_model.sdf' - ) - ] - ), - # Launch a bridge to forward tf and joint states to ros2 - Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=[ - '/world/default/model/double_pendulum_with_base0/joint_state@' - 'sensor_msgs/msg/JointState[gz.msgs.Model', - '/model/double_pendulum_with_base0/pose@' - 'tf2_msgs/msg/TFMessage[gz.msgs.Pose_V' - ], - remappings=[ - ('/model/double_pendulum_with_base0/pose', '/tf'), - ('/world/default/model/double_pendulum_with_base0/joint_state', '/joint_states') - ] - ), - # Launch rviz - Node( - package='rviz2', - executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')] - ) - ]) diff --git a/ros_gz_sim_demos/launch/tf_bridge.launch.xml b/ros_gz_sim_demos/launch/tf_bridge.launch.xml new file mode 100644 index 00000000..33f0949b --- /dev/null +++ b/ros_gz_sim_demos/launch/tf_bridge.launch.xml @@ -0,0 +1,6 @@ + + + + + +