diff --git a/ros_gz_sim_demos/CMakeLists.txt b/ros_gz_sim_demos/CMakeLists.txt index 8e0f580a..9b69104b 100644 --- a/ros_gz_sim_demos/CMakeLists.txt +++ b/ros_gz_sim_demos/CMakeLists.txt @@ -9,6 +9,12 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() +install( + DIRECTORY + config/ + DESTINATION share/${PROJECT_NAME}/config +) + install( DIRECTORY launch/ diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index c404a4dc..5519fc4c 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -102,7 +102,7 @@ GPU lidar data can be obtained as: Using the bridge: - ros2 launch ros_gz_sim_demos gpu_lidar_bridge.launch.py + ros2 launch ros_gz_sim_demos gpu_lidar_bridge.launch.xml *TODO*: Blocked by `ros_gz_point_cloud` [issue](https://github.com/gazebosim/ros_gz/issues/40). diff --git a/ros_gz_sim_demos/config/gpu_lidar.yaml b/ros_gz_sim_demos/config/gpu_lidar.yaml new file mode 100644 index 00000000..9970e084 --- /dev/null +++ b/ros_gz_sim_demos/config/gpu_lidar.yaml @@ -0,0 +1,18 @@ +# GPU lidar configuration. +- ros_topic_name: "/lidar" + gz_topic_name: "/lidar" + ros_type_name: "sensor_msgs/msg/LaserScan" + gz_type_name: "gz.msgs.LaserScan" + subscriber_queue: 5 + publisher_queue: 6 + lazy: false + direction: GZ_TO_ROS + +- ros_topic_name: "/lidar/points" + gz_topic_name: "/lidar/points" + ros_type_name: "sensor_msgs/msg/PointCloud2" + gz_type_name: "gz.msgs.PointCloudPacked" + subscriber_queue: 5 + publisher_queue: 6 + lazy: false + direction: GZ_TO_ROS \ No newline at end of file diff --git a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py deleted file mode 100644 index 42998efa..00000000 --- a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py +++ /dev/null @@ -1,65 +0,0 @@ -# Copyright 2019 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from launch.conditions import IfCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration - -from launch_ros.actions import Node - - -def generate_launch_description(): - - pkg_ros_gz_sim_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@gz.msgs.LaserScan', - '/lidar/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked'], - output='screen' - ) - - return LaunchDescription([ - gz_sim, - DeclareLaunchArgument('rviz', default_value='true', - description='Open RViz.'), - bridge, - rviz, - ]) diff --git a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.xml b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.xml new file mode 100644 index 00000000..a093e916 --- /dev/null +++ b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.xml @@ -0,0 +1,6 @@ + + + + + +