From 88b9cb8664237b8d3e0d55fcf8f75c6f1860950c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Mon, 4 Nov 2024 18:44:05 +0100 Subject: [PATCH 01/13] Refactor air pressure 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/config/air_pressure.yaml | 9 +++ ros_gz_sim_demos/launch/air_pressure.launch | 5 ++ .../launch/air_pressure.launch.py | 63 ------------------- 4 files changed, 20 insertions(+), 63 deletions(-) create mode 100644 ros_gz_sim_demos/config/air_pressure.yaml create mode 100644 ros_gz_sim_demos/launch/air_pressure.launch delete mode 100644 ros_gz_sim_demos/launch/air_pressure.launch.py 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/config/air_pressure.yaml b/ros_gz_sim_demos/config/air_pressure.yaml new file mode 100644 index 00000000..72c876af --- /dev/null +++ b/ros_gz_sim_demos/config/air_pressure.yaml @@ -0,0 +1,9 @@ +# Air pressure bridge configuration. +- ros_topic_name: "air_pressure" + gz_topic_name: "air_pressure" + ros_type_name: "sensor_msgs/msg/FluidPressure" + gz_type_name: "gz.msgs.FluidPressure" + subscriber_queue: 5 + publisher_queue: 6 + lazy: false + direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/air_pressure.launch b/ros_gz_sim_demos/launch/air_pressure.launch new file mode 100644 index 00000000..502690bd --- /dev/null +++ b/ros_gz_sim_demos/launch/air_pressure.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.py b/ros_gz_sim_demos/launch/air_pressure.launch.py deleted file mode 100644 index 2a422b34..00000000 --- a/ros_gz_sim_demos/launch/air_pressure.launch.py +++ /dev/null @@ -1,63 +0,0 @@ -# Copyright 2019 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. - -"""Launch Gazebo Sim with command line arguments.""" - -import os - -from ament_index_python.packages import get_package_share_directory - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from launch.conditions import IfCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration - -from launch_ros.actions import Node - - -def generate_launch_description(): - - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/air_pressure@sensor_msgs/msg/FluidPressure@gz.msgs.FluidPressure'], - parameters=[{'qos_overrides./air_pressure.publisher.reliability': 'best_effort'}], - output='screen' - ) - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={'gz_args': '-r sensors.sdf'}.items(), - ) - - # RQt - rqt = Node( - package='rqt_topic', - executable='rqt_topic', - arguments=['-t'], - condition=IfCondition(LaunchConfiguration('rqt')) - ) - return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rqt', default_value='true', - description='Open RQt.'), - bridge, - rqt - ]) From 63d3a13f1ef938c12ff9249b1a27866cf75018bb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Mon, 4 Nov 2024 18:53:34 +0100 Subject: [PATCH 02/13] Update README 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/README.md | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index c404a4dc..8b703e71 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -14,17 +14,12 @@ There's a convenient launch file, try for example: Publishes fluid pressure readings. - ros2 launch ros_gz_sim_demos air_pressure.launch.py + ros2 launch ros_gz_sim_demos air_pressure.launch -This demo also shows the use of custom QoS parameters. The sensor data is -published as as "best-effort", so trying to subscribe to "reliable" data won't -work. See the difference between: +You can subscribe to receive the data with: - ros2 topic echo /air_pressure --qos-reliability best_effort + ros2 topic echo /air_pressure -And - - ros2 topic echo /air_pressure --qos-reliability reliable ![](images/air_pressure_demo.png) From 75a6eaec1dafadce342f47c24d71e156badd83f5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Mon, 4 Nov 2024 20:03:03 +0100 Subject: [PATCH 03/13] Tweak 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/launch/air_pressure.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch b/ros_gz_sim_demos/launch/air_pressure.launch index 502690bd..b558cc39 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch +++ b/ros_gz_sim_demos/launch/air_pressure.launch @@ -1,5 +1,5 @@ - + From 1035a72a2dec87b3f8b9c7e818328af625d1cc71 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Mon, 4 Nov 2024 20:13:58 +0100 Subject: [PATCH 04/13] Run the GUI 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/launch/air_pressure.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch b/ros_gz_sim_demos/launch/air_pressure.launch index b558cc39..192d56ac 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch +++ b/ros_gz_sim_demos/launch/air_pressure.launch @@ -2,4 +2,5 @@ + From 643a69b9ca2f2630e103d082f90f276f5274c8f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Tue, 5 Nov 2024 14:52:12 +0100 Subject: [PATCH 05/13] Add xml extension 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/README.md | 2 +- .../launch/{air_pressure.launch => air_pressure.launch.xml} | 0 2 files changed, 1 insertion(+), 1 deletion(-) rename ros_gz_sim_demos/launch/{air_pressure.launch => air_pressure.launch.xml} (100%) diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index 8b703e71..44724dc5 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -14,7 +14,7 @@ There's a convenient launch file, try for example: Publishes fluid pressure readings. - ros2 launch ros_gz_sim_demos air_pressure.launch + ros2 launch ros_gz_sim_demos air_pressure.launch.xml You can subscribe to receive the data with: diff --git a/ros_gz_sim_demos/launch/air_pressure.launch b/ros_gz_sim_demos/launch/air_pressure.launch.xml similarity index 100% rename from ros_gz_sim_demos/launch/air_pressure.launch rename to ros_gz_sim_demos/launch/air_pressure.launch.xml From 8ee64d3c645a4404c363746ab41fb13a2adeb767 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 22 Nov 2024 17:11:07 +0100 Subject: [PATCH 06/13] Add QoS settings 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/launch/air_pressure.launch.xml | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.xml b/ros_gz_sim_demos/launch/air_pressure.launch.xml index 192d56ac..b2c6d33b 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.xml +++ b/ros_gz_sim_demos/launch/air_pressure.launch.xml @@ -1,6 +1,12 @@ - - - - + + + + From ceb0daeadb87785dc3853f2dba252432ef895224 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 22 Nov 2024 17:16:53 +0100 Subject: [PATCH 07/13] Restore README 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/README.md | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index 44724dc5..68ac90b3 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -16,10 +16,13 @@ Publishes fluid pressure readings. ros2 launch ros_gz_sim_demos air_pressure.launch.xml -You can subscribe to receive the data with: +This demo also shows the use of custom QoS parameters. The sensor data is published as as "best-effort", so trying to subscribe to "reliable" data won't work. See the difference between: - ros2 topic echo /air_pressure + ros2 topic echo /air_pressure --qos-reliability best_effort +And + + ros2 topic echo /air_pressure --qos-reliability reliable ![](images/air_pressure_demo.png) From 5d9f5f75153e3bceaab9b5e3cf5fe2bed1bb5d6c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 22 Nov 2024 17:17:31 +0100 Subject: [PATCH 08/13] Tweak 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/README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index 68ac90b3..62c670f9 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -16,7 +16,9 @@ Publishes fluid pressure readings. ros2 launch ros_gz_sim_demos air_pressure.launch.xml -This demo also shows the use of custom QoS parameters. The sensor data is published as as "best-effort", so trying to subscribe to "reliable" data won't work. See the difference between: +This demo also shows the use of custom QoS parameters. The sensor data is +published as as "best-effort", so trying to subscribe to "reliable" data won't +work. See the difference between: ros2 topic echo /air_pressure --qos-reliability best_effort From 608328c1e9b21fc0525ac7d3bcfe25c86e97ac9f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 22 Nov 2024 17:23:40 +0100 Subject: [PATCH 09/13] Tweak 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/config/air_pressure.yaml | 7 ++----- ros_gz_sim_demos/launch/air_pressure.launch.xml | 3 ++- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/ros_gz_sim_demos/config/air_pressure.yaml b/ros_gz_sim_demos/config/air_pressure.yaml index 72c876af..36ad5f67 100644 --- a/ros_gz_sim_demos/config/air_pressure.yaml +++ b/ros_gz_sim_demos/config/air_pressure.yaml @@ -1,9 +1,6 @@ # Air pressure bridge configuration. -- ros_topic_name: "air_pressure" - gz_topic_name: "air_pressure" +- topic_name: "air_pressure" ros_type_name: "sensor_msgs/msg/FluidPressure" gz_type_name: "gz.msgs.FluidPressure" - subscriber_queue: 5 - publisher_queue: 6 - lazy: false + lazy: true direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.xml b/ros_gz_sim_demos/launch/air_pressure.launch.xml index b2c6d33b..328e01ea 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.xml +++ b/ros_gz_sim_demos/launch/air_pressure.launch.xml @@ -6,7 +6,8 @@ + use_composition="True" + bridge_params="'qos_overrides./air_pressure.publisher.reliability': 'best_effort'" /> From e724cb32e381119bc259e3de86f156207630adf6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 6 Dec 2024 17:58:04 +0100 Subject: [PATCH 10/13] Pass QoS settings to rqt_topic 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/launch/air_pressure.launch.xml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.xml b/ros_gz_sim_demos/launch/air_pressure.launch.xml index 328e01ea..ba8447ea 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.xml +++ b/ros_gz_sim_demos/launch/air_pressure.launch.xml @@ -8,6 +8,8 @@ config_file="$(find-pkg-share ros_gz_sim_demos)/config/air_pressure.yaml" use_composition="True" bridge_params="'qos_overrides./air_pressure.publisher.reliability': 'best_effort'" /> - + + + From 2868471b4dcc32fd363cbee1cfc5a0554dd55b7e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 6 Dec 2024 18:14:25 +0100 Subject: [PATCH 11/13] Update ros_gz_sim_demos/launch/air_pressure.launch.xml MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Addisu Z. Taddese Signed-off-by: Carlos Agüero --- ros_gz_sim_demos/launch/air_pressure.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.xml b/ros_gz_sim_demos/launch/air_pressure.launch.xml index ba8447ea..369da0ae 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.xml +++ b/ros_gz_sim_demos/launch/air_pressure.launch.xml @@ -1,8 +1,8 @@ + use_composition="true" + create_own_container="true" /> Date: Fri, 6 Dec 2024 18:14:32 +0100 Subject: [PATCH 12/13] Update ros_gz_sim_demos/launch/air_pressure.launch.xml MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Addisu Z. Taddese Signed-off-by: Carlos Agüero --- ros_gz_sim_demos/launch/air_pressure.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.xml b/ros_gz_sim_demos/launch/air_pressure.launch.xml index 369da0ae..6fcac46b 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.xml +++ b/ros_gz_sim_demos/launch/air_pressure.launch.xml @@ -6,7 +6,7 @@ From 1ebf6ba1840d45743046762115901349d4346bf4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 11 Dec 2024 17:07:34 +0100 Subject: [PATCH 13/13] Update ros_gz_sim_demos/launch/air_pressure.launch.xml MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Carlos Agüero --- ros_gz_sim_demos/launch/air_pressure.launch.xml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.xml b/ros_gz_sim_demos/launch/air_pressure.launch.xml index 6fcac46b..9fd33397 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.xml +++ b/ros_gz_sim_demos/launch/air_pressure.launch.xml @@ -6,8 +6,9 @@ + use_composition="true"> + +