From da80ba7b232656e52650ca583d826bd799fc53f7 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 11 Aug 2022 11:16:19 -0700 Subject: [PATCH] Refine ros_gz_shims Co-authored-by: Louise Poubel --- ros_gz_shims/README.md | 2 +- ros_gz_shims/ros_ign/README.md | 2 +- ros_gz_shims/ros_ign/package.xml | 6 +- .../src/parameter_bridge_shim.cpp | 15 +- .../ros_ign_bridge/src/static_bridge_shim.cpp | 15 +- ros_gz_shims/ros_ign_gazebo/CMakeLists.txt | 18 ++ ros_gz_shims/ros_ign_gazebo/README.md | 2 + .../ros_ign_gazebo/src/create_shim.cpp | 15 +- .../ros_ign_gazebo_demos/CMakeLists.txt | 12 - .../launch/air_pressure.launch.py | 43 +-- .../launch/battery.launch.py | 49 +--- .../launch/camera.launch.py | 41 +-- .../launch/depth_camera.launch.py | 57 +--- .../launch/diff_drive.launch.py | 47 +--- .../launch/gpu_lidar.launch.py | 45 +-- .../launch/gpu_lidar_bridge.launch.py | 43 +-- .../launch/image_bridge.launch.py | 45 +-- .../ros_ign_gazebo_demos/launch/imu.launch.py | 58 +--- .../launch/joint_states.launch.py | 82 +----- .../launch/magnetometer.launch.py | 43 +-- .../launch/rgbd_camera.launch.py | 43 +-- .../launch/rgbd_camera_bridge.launch.py | 48 +--- .../robot_description_publisher.launch.py | 73 +---- .../launch/tf_bridge.launch.py | 41 +-- .../launch/triggered_camera.launch.py | 40 +-- .../models/double_pendulum_model.sdf | 266 ------------------ .../ros_ign_gazebo_demos/models/rrbot.xacro | 165 ----------- .../ros_ign_gazebo_demos/rviz/camera.rviz | 137 --------- .../rviz/depth_camera.rviz | 147 ---------- .../ros_ign_gazebo_demos/rviz/diff_drive.rviz | 123 -------- .../ros_ign_gazebo_demos/rviz/gpu_lidar.rviz | 181 ------------ .../rviz/gpu_lidar_bridge.rviz | 167 ----------- .../ros_ign_gazebo_demos/rviz/imu.rviz | 130 --------- .../rviz/joint_states.rviz | 190 ------------- .../rviz/rgbd_camera.rviz | 159 ----------- .../rviz/rgbd_camera_bridge.rviz | 142 ---------- .../rviz/robot_description_publisher.rviz | 148 ---------- .../ros_ign_gazebo_demos/rviz/tf_bridge.rviz | 163 ----------- .../ros_ign_image/src/image_bridge_shim.cpp | 15 +- 39 files changed, 189 insertions(+), 2829 deletions(-) create mode 100644 ros_gz_shims/ros_ign_gazebo/README.md delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz delete mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz diff --git a/ros_gz_shims/README.md b/ros_gz_shims/README.md index b653a6fc..17007f4e 100644 --- a/ros_gz_shims/README.md +++ b/ros_gz_shims/README.md @@ -10,4 +10,4 @@ ros2 run ros_gz parameter_bridge [...] ros2 run ros_ign parameter_bridge [...] # Will emit deprecation warning ``` -Additionally, installed files like launchfiles, message interfaces etc. are **duplicated** versions of the ones in `ros_gz` (but renamed as appropriate), and point to `ros_gz` dependencies as well (e.g. launchfiles pointing to `ros_gz` nodes.) +Additionally, installed files like launch files, message interfaces etc. are **duplicated** versions of the ones in `ros_gz` (but renamed as appropriate), and point to `ros_gz` dependencies as well (e.g. launch files pointing to `ros_gz` nodes.) diff --git a/ros_gz_shims/ros_ign/README.md b/ros_gz_shims/ros_ign/README.md index d6f36599..7f2dcc88 100644 --- a/ros_gz_shims/ros_ign/README.md +++ b/ros_gz_shims/ros_ign/README.md @@ -1,2 +1,2 @@ # This is a shim meta-package -For [ros_gz](https://github.com/gazebosim/ros_gz) +For [ros_gz](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz) diff --git a/ros_gz_shims/ros_ign/package.xml b/ros_gz_shims/ros_ign/package.xml index 03e41bcb..be76f307 100644 --- a/ros_gz_shims/ros_ign/package.xml +++ b/ros_gz_shims/ros_ign/package.xml @@ -1,11 +1,9 @@ - ros_ign 0.0.1 - Shim meta-package to redirect to ros_gz. + Shim meta-package to redirect to ros_gz. Brandon Ong Apache 2.0 @@ -16,8 +14,6 @@ ros_ign_gazebo ros_ign_gazebo_demos ros_ign_image - - ament_lint_auto ament_lint_common diff --git a/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp index b6b613e5..df6882bb 100644 --- a/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp +++ b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp @@ -1,6 +1,19 @@ +// 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. + // Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_bridge parameter_bridge" -#include #include #include #include diff --git a/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp index 56c577b8..4ee0fdde 100644 --- a/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp +++ b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp @@ -1,6 +1,19 @@ +// 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. + // Shim to redirect "ros_ign_bridge static_bridge" call to "ros_gz_bridge static_bridge" -#include #include #include #include diff --git a/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt index 86974a76..78d8ef96 100644 --- a/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt +++ b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt @@ -22,6 +22,24 @@ ament_export_dependencies( ros_gz_bridge ) +# Edifice +if("$ENV{GZ_VERSION}" STREQUAL "edifice") + find_package(ignition-gazebo5 REQUIRED) + set(GZ_SIM_VER ${ignition-gazebo5_VERSION_MAJOR}) + message(STATUS "Compiling against Gazebo Edifice") +# Garden +elseif("$ENV{GZ_VERSION}" STREQUAL "garden") + find_package(gz-sim7 REQUIRED) + set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) + set(GZ_TARGET_PREFIX gz) + message(STATUS "Compiling against Gazebo Garden") +# Default to Fortress +else() + find_package(ignition-gazebo6 REQUIRED) + set(GZ_SIM_VER ${ignition-gazebo6_VERSION_MAJOR}) + message(STATUS "Compiling against Gazebo Fortress") +endif() + configure_file( launch/ign_gazebo.launch.py.in launch/ign_gazebo.launch.py.configured diff --git a/ros_gz_shims/ros_ign_gazebo/README.md b/ros_gz_shims/ros_ign_gazebo/README.md new file mode 100644 index 00000000..2df45d4a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_sim) diff --git a/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp index dbaa029e..8a6d366a 100644 --- a/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp +++ b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp @@ -1,6 +1,19 @@ +// 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. + // Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_sim parameter_bridge" -#include #include #include #include diff --git a/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt index 0a7ae4fe..68b53fed 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt +++ b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt @@ -14,16 +14,4 @@ install( DESTINATION share/${PROJECT_NAME}/launch ) -install( - DIRECTORY - rviz/ - DESTINATION share/${PROJECT_NAME}/rviz -) - -install( - DIRECTORY - models/ - DESTINATION share/${PROJECT_NAME}/models -) - ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py index 272d6eb1..1633d4c0 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -12,52 +12,23 @@ # 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - 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@ignition.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(), - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - # 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 + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'air_pressure.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py index 4e32322a..a58b334d 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,53 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - # RQt - rqt = Node( - package='rqt_plot', - executable='rqt_plot', - # FIXME: Why isn't the topic being populated on the UI? RQt issue? - arguments=['--force-discover', - '/model/vehicle_blue/battery/linear_battery/state/percentage'], - condition=IfCondition(LaunchConfiguration('rqt')) - ) - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={ - 'gz_args': '-r -z 1000000 linear_battery_demo.sdf' - }.items(), - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=[ - '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', - '/model/vehicle_blue/battery/linear_battery/state@sensor_msgs/msg/BatteryState@' - 'ignition.msgs.BatteryState' - ], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rqt', default_value='true', - description='Open RQt.'), - bridge, - rqt + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'battery.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py index 1bd9a8a0..c90633f6 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,47 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={'gz_args': '-r camera_sensor.sdf'}.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', - '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], - output='screen' - ) return LaunchDescription([ - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - gz_sim, - bridge, - rviz + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'camera.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py index d42ce862..f8760328 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,61 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') - ), - # launch_arguments={ - # 'gz_args': '-r depth_camera.sdf' - # }.items(), - ) - - # RQt - rqt = Node( - package='rqt_image_view', - executable='rqt_image_view', - arguments=['/camera'], - condition=IfCondition(LaunchConfiguration('rqt')) - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - # FIXME: Generate new RViz config once this demo is usable again - # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'depth_camera.rviz')], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/depth_camera@sensor_msgs/msg/Image@ignition.msgs.Image'], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - DeclareLaunchArgument('rqt', default_value='true', - description='Open RQt.'), - bridge, - rviz, - rqt + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'depth_camera.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py index 8a297567..c1eba4fe 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,53 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={ - 'gz_args': '-r diff_drive.sdf' - }.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'diff_drive.rviz')], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', - '/model/vehicle_blue/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry', - '/model/vehicle_green/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', - '/model/vehicle_green/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry'], - parameters=[{'qos_overrides./model/vehicle_blue.subscriber.reliability': 'reliable', - 'qos_overrides./model/vehicle_green.subscriber.reliability': 'reliable'}], - output='screen' - ) return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - bridge, - rviz + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'diff_drive.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py index 5cfdb08f..86d180d0 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,49 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - # launch_arguments={ - # 'gz_args': '-r gpu_lidar.sdf' - # }.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - # FIXME: Generate new RViz config once this demo is usable again - # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar.rviz')], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan/'], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_gz_point_cloud/ return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - bridge, - rviz + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'imu.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py index 26bd36b8..798d17e6 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,49 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={ - 'gz_args': '-r gpu_lidar_sensor.sdf' - }.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan', - '/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked'], - output='screen' - ) return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - bridge, - rviz, + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'gpu_lidar_bridge.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py index 91e81e33..79fb5e58 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,49 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={ - 'gz_args': '-r sensors_demo.sdf' - }.items(), - ) - - # RQt - rqt = Node( - package='rqt_image_view', - executable='rqt_image_view', - arguments=[LaunchConfiguration('image_topic')], - condition=IfCondition(LaunchConfiguration('rqt')) - ) - - # Bridge - bridge = Node( - package='ros_gz_image', - executable='image_bridge', - arguments=['camera', 'depth_camera', 'rgbd_camera/image', 'rgbd_camera/depth_image'], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rqt', default_value='true', - description='Open RQt.'), - DeclareLaunchArgument('image_topic', default_value='/camera', - description='Topic to start viewing in RQt.'), - bridge, - rqt + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'image_bridge.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py index 649ad359..86d180d0 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,62 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - 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')) - ) - - # RViz - # FIXME: Add once there's an IMU display for RViz2 - # pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - # rviz = Node( - # package='rviz2', - # executable='rviz2', - # # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'imu.rviz')], - # condition=IfCondition(LaunchConfiguration('rviz')) - # ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/imu@sensor_msgs/msg/Imu@ignition.msgs.IMU'], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') return LaunchDescription([ - gz_sim, - DeclareLaunchArgument( - 'rqt', default_value='true', description='Open RQt.' - ), - DeclareLaunchArgument( - 'rviz', default_value='true', description='Open RViz.' - ), - bridge, - rqt - # rviz + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'imu.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py index 20b330ec..527e8b37 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -15,84 +15,20 @@ import os from ament_index_python.packages import get_package_share_directory + from launch import LaunchDescription from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.actions import Node -import xacro def generate_launch_description(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - # Package Directories - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - # Parse robot description from xacro - robot_description_file = os.path.join(pkg_ros_gz_sim_demos, 'models', 'rrbot.xacro') - robot_description_config = xacro.process_file( - robot_description_file - ) - robot_description = {'robot_description': robot_description_config.toxml()} - - # Robot state publisher - robot_state_publisher = Node( - package='robot_state_publisher', - executable='robot_state_publisher', - name='robot_state_publisher', - output='both', - parameters=[robot_description], - ) - - # Gazebo Sim - gazebo = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') - ), - launch_arguments={'gz_args': '-r empty.sdf'}.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'joint_states.rviz')], - ) - - # Spawn - spawn = Node( - package='ros_gz_sim', - executable='create', - arguments=[ - '-name', 'rrbot', - '-topic', 'robot_description', - ], - output='screen', - ) - - # Gz - ROS Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=[ - # Clock (IGN -> ROS2) - '/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock', - # Joint states (IGN -> ROS2) - '/world/empty/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model', - ], - remappings=[ - ('/world/empty/model/rrbot/joint_state', 'joint_states'), - ], - output='screen' - ) - - return LaunchDescription( - [ - # Nodes and Launches - gazebo, - spawn, - bridge, - robot_state_publisher, - rviz, - ] - ) + return LaunchDescription([ + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'joint_states.launch.py')), + ) + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py index 0e026676..6820d445 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,47 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - 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')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/magnetometer@sensor_msgs/msg/MagneticField@ignition.msgs.Magnetometer'], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rqt', default_value='true', - description='Open RQt.'), - bridge, - rqt + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'magnetometer.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py index 1ec8409b..6735d4bc 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,47 +17,18 @@ 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.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.actions import Node - def generate_launch_description(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - # launch_arguments={ - # 'gz_args': '-r rgbd_camera.sdf' - # }.items(), - ) - - # FIXME: need rviz configuration migration - # rviz = Node( - # package='rviz2', - # executable='rviz2', - # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera.rviz')], - # condition=IfCondition(LaunchConfiguration('rviz')) - # ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', - '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image'], - output='screen' - ) + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud/ return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - bridge, - # rviz, + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'rgbd_camera.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py index a318f682..1fb5ba19 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -17,54 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={ - 'gz_args': '-r sensors_demo.sdf' - }.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=[ - '-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera_bridge.rviz') - ], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=[ - '/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', - '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image', - '/rgbd_camera/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked' - ], - output='screen' - ) return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - bridge, - rviz, + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'rgbd_camera_bridge.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py index 882cdee3..f0adf53e 100755 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py @@ -1,4 +1,4 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. +# 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. @@ -20,74 +20,17 @@ from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.actions import Node - def generate_launch_description(): - # Import the model urdf (load from file, xacro ...) - robot_desc = \ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - ''\ - '' - - # Robot state publisher - params = {'use_sim_time': True, 'robot_description': robot_desc} - robot_state_publisher = Node( - package='robot_state_publisher', - executable='robot_state_publisher', - name='robot_state_publisher', - output='screen', - parameters=[params], - arguments=[]) + print("ros_ign_gazebo_demos is deprecated!Please use ros_gz_sim_demos instead!") - # Gazebo Sim - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - gazebo = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={'gz_args': '-r empty.sdf'}.items(), - ) - - # RViz pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=[ - '-d', - os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'robot_description_publisher.rviz') - ] - ) - - # Spawn - spawn = Node(package='ros_gz_sim', executable='create', - arguments=[ - '-name', 'my_custom_model', - '-x', '1.2', - '-z', '2.3', - '-Y', '3.4', - '-topic', '/robot_description'], - output='screen') return LaunchDescription([ - gazebo, - robot_state_publisher, - rviz, - spawn + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, + 'launch', + 'robot_description_publisher.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py index 3b2171d0..d4cfb01b 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py @@ -17,43 +17,18 @@ 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 +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource def generate_launch_description(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + return LaunchDescription([ - # Launch gazebo - ExecuteProcess( - cmd=[ - 'ign', 'gazebo', '-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[ignition.msgs.Model', - '/model/double_pendulum_with_base0/pose@' - 'tf2_msgs/msg/TFMessage[ignition.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')] + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'tf_bridge.launch.py')), ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py index 9e6362a2..984f4c61 100644 --- a/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py @@ -17,48 +17,18 @@ 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(): + print("ros_ign_gazebo_demos is deprecated! Please use ros_gz_sim_demos instead!") pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') - pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - - gz_sim = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments={'gz_args': '-r triggered_camera_sensor.sdf'}.items(), - ) - - # RViz - rviz = Node( - package='rviz2', - executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], - condition=IfCondition(LaunchConfiguration('rviz')) - ) - - # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', - '/camera/trigger@std_msgs/msg/Bool@ignition.msgs.Boolean', - '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], - output='screen' - ) return LaunchDescription([ - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - gz_sim, - bridge, - rviz + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim_demos, 'launch', 'triggered_camera.launch.py')), + ) ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf deleted file mode 100644 index 91e072e4..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf +++ /dev/null @@ -1,266 +0,0 @@ - - - - - 0.001 - 1 - - - - true - 0 0 10 0 0 0 - 0.8 0.8 0.8 1 - 0.2 0.2 0.2 1 - - 1000 - 0.9 - 0.01 - 0.001 - - -0.5 0.1 -0.9 - - - - true - - - - - 0 0 1 - 100 100 - - - - - - - 0 0 1 - 100 100 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - - - - 0 0 0 0 0 0 - - - - 100 - - - 0 0 0.01 0 0 0 - - - 0.8 - 0.02 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - -0.275 0 1.1 0 0 0 - - - 0.2 0.2 2.2 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - 0 0 0.01 0 0 0 - - - 0.8 - 0.02 - - - - - -0.275 0 1.1 0 0 0 - - - 0.2 0.2 2.2 - - - - - - - 0 0 2.1 -1.5708 0 0 - 0 - - 0 0 0.5 0 0 0 - - - -0.05 0 0 0 1.5708 0 - - - 0.1 - 0.3 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - 0 0 1.0 0 1.5708 0 - - - 0.1 - 0.2 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - 0 0 0.5 0 0 0 - - - 0.1 - 0.9 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - -0.05 0 0 0 1.5708 0 - - - 0.1 - 0.3 - - - - - 0 0 1.0 0 1.5708 0 - - - 0.1 - 0.2 - - - - - 0 0 0.5 0 0 0 - - - 0.1 - 0.9 - - - - - - - 0.25 1.0 2.1 -2 0 0 - 0 - - 0 0 0.5 0 0 0 - - - 0 0 0 0 1.5708 0 - - - 0.08 - 0.3 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - 0 0 0.5 0 0 0 - - - 0.1 - 0.9 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - 0 0 0 0 1.5708 0 - - - 0.08 - 0.3 - - - - - 0 0 0.5 0 0 0 - - - 0.1 - 0.9 - - - - - - - base - upper_link - - 1.0 0 0 - - - - - upper_link - lower_link - - 1.0 0 0 - - - - - - - - true - - true - - - - - - diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro deleted file mode 100644 index 00680c14..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro +++ /dev/null @@ -1,165 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - - - - - - 0.2 - 0.2 - - 0 0 0 1 - 0 0 0 1 - 0 0 0 1 - - - - - - 0.2 - 0.2 - - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - - - - - - - - - \ No newline at end of file diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz deleted file mode 100644 index 81398197..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz +++ /dev/null @@ -1,137 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Camera1 - - /Camera1/Status1 - - /Image1 - Splitter Ratio: 0.5 - Tree Height: 557 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Class: rviz_default_plugins/Camera - Enabled: true - Image Rendering: background and overlay - Name: Camera - Overlay Alpha: 0.5 - Queue Size: 10 - Topic: /camera - Unreliable: false - Value: true - Visibility: - Grid: true - Image: true - Value: true - Zoom Factor: 1 - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 10 - Topic: /camera - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: camera/link/camera - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: /move_base_simple/goal - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 19.73822784423828 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.7903980016708374 - Target Frame: - Value: Orbit (rviz) - Yaw: 0.785398006439209 - Saved: ~ -Window Geometry: - Camera: - collapsed: false - Displays: - collapsed: false - Height: 702 - Hide Left Dock: false - Hide Right Dock: false - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000015600000268fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000268000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001c700000268fc0200000005fb0000000c00430061006d006500720061010000003b0000011f0000002800fffffffb0000000a0049006d0061006700650100000160000001430000002800fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000000320000026800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 859 - X: 517 - Y: 361 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz deleted file mode 100644 index 6957e15f..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz +++ /dev/null @@ -1,147 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Image1 - - /PointCloud21 - Splitter Ratio: 0.5 - Tree Height: 423 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: Image -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Class: rviz/Image - Enabled: true - Image Topic: /depth_camera - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.019999999552965164 - Style: Flat Squares - Topic: /depth_camera/points - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Global Options: - Background Color: 255; 255; 255 - Default Light: true - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 6.307931423187256 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: -0.024829570204019547 - Y: -0.440496027469635 - Z: 1.0747597217559814 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: -1.3397971391677856 - Target Frame: - Value: Orbit (rviz) - Yaw: 4.723598957061768 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 568 - Hide Left Dock: false - Hide Right Dock: false - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000001e2fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610000000272000000c1000000000000000000000001000001b8000001e2fc0200000006fb0000000a0049006d006100670065010000003b000001e20000001600fffffffb0000000c00430061006d00650072006100000001ae000001850000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000196000001e200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1200 - X: 405 - Y: 378 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz deleted file mode 100644 index e647f4c9..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz +++ /dev/null @@ -1,123 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Odometry1 - - /Odometry1/Status1 - Splitter Ratio: 0.5 - Tree Height: 701 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Angle Tolerance: 0.10000000149011612 - Class: rviz_default_plugins/Odometry - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Keep: 1000 - Name: Odometry - Position Tolerance: 0.10000000149011612 - Shape: - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Color: 255; 25; 0 - Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 - Value: Arrow - Topic: /model/vehicle_blue/odometry - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: vehicle_blue/odom - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: /move_base_simple/goal - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 68.66040802001953 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: -1.2689772844314575 - Y: 10.203336715698242 - Z: -2.8907392024993896 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 1.5697963237762451 - Target Frame: - Value: Orbit (rviz) - Yaw: 0.8253979682922363 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 846 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000023d000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000026d000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1200 - X: 325 - Y: 158 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz deleted file mode 100644 index 9161d0c8..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz +++ /dev/null @@ -1,181 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /LaserScan1 - - /PointCloud21 - Splitter Ratio: 0.5 - Tree Height: 366 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: LaserScan -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserScan - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.029999999329447746 - Style: Flat Squares - Topic: /lidar - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.029999999329447746 - Style: Flat Squares - Topic: /custom_params/pc2 - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: custom_params/link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 10.596034049987793 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 1.855783224105835 - Y: -0.6233639717102051 - Z: 0.7489486932754517 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.5402030348777771 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.7535903453826904 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 511 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000001a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001b8000002f8fc0200000006fb0000000a0049006d006100670065000000003b0000016d0000000000000000fb0000000c00430061006d006500720061000000003b000002f80000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000161000001a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 701 - X: 352 - Y: 269 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz deleted file mode 100644 index 42968c2b..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz +++ /dev/null @@ -1,167 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /LaserScan1/Status1 - - /PointCloud21/Status1 - Splitter Ratio: 0.504601240158081 - Tree Height: 701 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserScan - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /lidar - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: "" - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /lidar - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: model_with_lidar/link/gpu_lidar - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: /move_base_simple/goal - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 15.735194206237793 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 2.550645589828491 - Y: -0.290515273809433 - Z: -1.1467934846878052 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.7253980040550232 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.7385823726654053 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 846 - Hide Left Dock: false - Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001ef000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000002bb000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1200 - X: 338 - Y: 1176 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz deleted file mode 100644 index 0169390a..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz +++ /dev/null @@ -1,130 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Imu1 - - /Imu1/Status1 - Splitter Ratio: 0.5 - Tree Height: 352 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 1 - Class: rviz_plugin_tutorials/Imu - Color: 204; 51; 204 - Enabled: true - History Length: 1 - Name: Imu - Topic: /imu - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: sensors/sensors_box/link/imu - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 33.22251510620117 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: -1.7206333875656128 - Y: -0.9246708154678345 - Z: 1.870512843132019 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.785398006439209 - Target Frame: - Value: Orbit (rviz) - Yaw: 0.785398006439209 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 575 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000191000001e9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003d70000003efc0100000002fb0000000800540069006d00650000000000000003d70000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000001a2000001e900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 825 - X: 751 - Y: 92 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz deleted file mode 100644 index 06920d70..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz +++ /dev/null @@ -1,190 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - - /RobotModel1 - - /TF1 - Splitter Ratio: 0.5 - Tree Height: 802 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 0.800000011920929 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - link1: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - link2: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - link3: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Name: RobotModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_default_plugins/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: true - link1: - Value: true - link2: - Value: true - link3: - Value: true - world: - Value: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - link1: - link2: - link3: - {} - world: - {} - Update Interval: 0 - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: world - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /goal_pose - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 6.524543762207031 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: -0.106326624751091 - Y: 0.5023337006568909 - Z: 1.1979976892471313 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.7303980588912964 - Target Frame: - Value: Orbit (rviz) - Yaw: 5.698581218719482 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1025 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000003abfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003ab000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003ab000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004cc000003ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1853 - X: 67 - Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz deleted file mode 100644 index d6933fc6..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz +++ /dev/null @@ -1,159 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /PointCloud21 - - /Image2 - Splitter Ratio: 0.5 - Tree Height: 317 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: Image -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Class: rviz/Image - Enabled: true - Image Topic: /rgbd_camera/depth_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.029999999329447746 - Style: Flat Squares - Topic: /default_params/points - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /rgbd_camera/image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: default_params - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 3.1044178009033203 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: -0.04919945076107979 - Y: -0.08779548853635788 - Z: 2.6499500274658203 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: -1.3547965288162231 - Target Frame: - Value: Orbit (rviz) - Yaw: 4.718593597412109 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 540 - Hide Left Dock: false - Hide Right Dock: false - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000001c6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000012d000001c6fc0200000007fb0000000a0049006d006100670065010000003b000000d60000001600fffffffb0000000a0049006d0061006700650100000117000000ea0000001600fffffffc000001ce000001650000000000fffffffa000000000100000002fb0000000a0049006d0061006700650100000000ffffffff0000000000000000fb0000000c00430061006d006500720061000000044c000000640000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d006501000000000000045000000000000000000000011a000001c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 937 - X: 147 - Y: 349 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz deleted file mode 100644 index 58955045..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz +++ /dev/null @@ -1,142 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /PointCloud21/Status1 - Splitter Ratio: 0.3251533806324005 - Tree Height: 701 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Flat Squares - Topic: /rgbd_camera/points - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 10 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: false - Queue Size: 10 - Topic: /rgbd_camera/depth_image - Unreliable: false - Value: true - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 10 - Topic: /rgbd_camera/image - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: rgbd_camera/link/rgbd_camera - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: /move_base_simple/goal - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 5.996953964233398 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.10905617475509644 - Y: 0.08000272512435913 - Z: 0.346417099237442 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.29039809107780457 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.0753986835479736 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 846 - Hide Left Dock: false - Hide Right Dock: false - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd000000040000000000000174000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000005fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0049006d006100670065010000003b000002020000002800fffffffb0000000a0049006d0061006700650100000243000000f00000002800fffffffb0000000a0056006900650077007300000000cf00000264000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000221000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1200 - X: 375 - Y: 1116 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz deleted file mode 100644 index 058a47f4..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz +++ /dev/null @@ -1,148 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /RobotModel1/Description Topic1 - Splitter Ratio: 0.5 - Tree Height: 878 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 77; 77; 79 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 50 - Reference Frame: - Value: true - - Alpha: 1 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Name: RobotModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - Enabled: true - Global Options: - Background Color: 207; 207; 207 - Fixed Frame: link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /move_base_simple/goal - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 49.51093292236328 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.8779783248901367 - Y: 0.15285056829452515 - Z: 0.762141764163971 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.6602023243904114 - Target Frame: - Value: Orbit (rviz) - Yaw: 4.142223358154297 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1023 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000222000003a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000198000003a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 960 - X: 898 - Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz deleted file mode 100644 index 76c42557..00000000 --- a/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz +++ /dev/null @@ -1,163 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - - /TF1 - - /TF1/Frames1 - Splitter Ratio: 0.516339898109436 - Tree Height: 549 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz_common/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Class: rviz_default_plugins/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: true - double_pendulum_with_base0: - Value: true - double_pendulum_with_base0/base: - Value: true - double_pendulum_with_base0/lower_link: - Value: true - double_pendulum_with_base0/upper_link: - Value: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - double_pendulum_with_base0: - double_pendulum_with_base0/base: - {} - double_pendulum_with_base0/lower_link: - {} - double_pendulum_with_base0/upper_link: - {} - Update Interval: 0 - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: double_pendulum_with_base0 - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Covariance x: 0.25 - Covariance y: 0.25 - Covariance yaw: 0.06853891909122467 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /goal_pose - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 8.114859580993652 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.3453984260559082 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.2535715103149414 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 846 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd0000000400000000000002ff000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000066f0000003efc0100000002fb0000000800540069006d006501000000000000066f000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000255000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1647 - X: 251 - Y: 169 diff --git a/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp index c004a7dc..0d44a1cb 100644 --- a/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp +++ b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp @@ -1,6 +1,19 @@ +// 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. + // Shim to redirect "ros_ign_image image_bridge" call to "ros_gz_image image_bridge" -#include #include #include #include