ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to start multiple Lidar in one file in ros2 environment

asked 2021-08-02 06:12:41 -0500

ylh gravatar image

updated 2021-08-05 04:30:23 -0500

Hello, friends. In ros1,Ican start two lidar in a file,like this: https://github.com/JeongJae0815/Multi... it use the <group>label.It's a ros1 sytle,the launch file write in XML. But in ros2,the launch file wite by python,how to start multiple Lidar in one file in ros2 environment?I'm a beginner to the velodyne_ros2_driver.The official driver is https://github.com/ros-drivers/velody.... I dont know how to start two velodyne in a launch file.I am looking forward to your reply, my friend.

Official launch of a velodyne_16 file:

import os
import yaml

import ament_index_python.packages
import launch
import launch_ros.actions


def generate_launch_description():
    driver_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_driver')
    driver_params_file = os.path.join(driver_share_dir, 'config', 'VLP16-velodyne_driver_node-params.yaml')
    velodyne_driver_node = launch_ros.actions.Node(package='velodyne_driver',
                                                   node_executable='velodyne_driver_node',
                                                   output='both',
                                                   parameters=[driver_params_file])

    convert_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
    convert_params_file = os.path.join(convert_share_dir, 'config', 'VLP16-velodyne_convert_node-params.yaml')
    with open(convert_params_file, 'r') as f:
        convert_params = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
    convert_params['calibration'] = os.path.join(convert_share_dir, 'params', 'VLP16db.yaml')
    velodyne_convert_node = launch_ros.actions.Node(package='velodyne_pointcloud',
                                                    node_executable='velodyne_convert_node',
                                                    output='both',
                                                    parameters=[convert_params])

    laserscan_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_laserscan')
    laserscan_params_file = os.path.join(laserscan_share_dir, 'config', 'default-velodyne_laserscan_node-params.yaml')
    velodyne_laserscan_node = launch_ros.actions.Node(package='velodyne_laserscan',
                                                      node_executable='velodyne_laserscan_node',
                                                      output='both',
                                                      parameters=[laserscan_params_file])


    return launch.LaunchDescription([velodyne_driver_node,
                                     velodyne_convert_node,
                                     velodyne_laserscan_node,

                                     launch.actions.RegisterEventHandler(
                                         event_handler=launch.event_handlers.OnProcessExit(
                                             target_action=velodyne_driver_node,
                                             on_exit=[launch.actions.EmitEvent(
                                                 event=launch.events.Shutdown())],
                                         )),
                                     ])

How do we write with <group> when multiple are started?friends.Thanks in advance! /_\

edit retag flag offensive close merge delete

Comments

Declaring two Nodes with different names or different namespaces should work. ROS2 also have group launch action, you can refer to turtlebot3 GitHub page to see some examples

Fetullah Atas gravatar image Fetullah Atas  ( 2021-08-02 16:41:31 -0500 )edit

Here is another example of a group launch from navigation2 https://github.com/ros-planning/navig...

Fetullah Atas gravatar image Fetullah Atas  ( 2021-08-02 16:43:43 -0500 )edit

My friend, thank you very much for your reply, which is very helpful to me!

ylh gravatar image ylh  ( 2021-08-02 20:44:27 -0500 )edit

You may also need to remap topics so that they don’t publish to same topic

Fetullah Atas gravatar image Fetullah Atas  ( 2021-08-02 23:45:49 -0500 )edit

Ok, my friend, I'll try it

ylh gravatar image ylh  ( 2021-08-03 00:41:37 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2021-08-05 04:28:03 -0500

ylh gravatar image

updated 2021-08-05 19:45:45 -0500

I have solved this problem with the help of friend ,Fetullah Atas ,and this tutorial: https://roboticsbackend.com/ros2-laun... following code:

import os
import yaml

import ament_index_python.packages
from launch import LaunchDescription
from launch_ros.actions import Node

#velodyne_1
def generate_launch_description():
    ld = LaunchDescription()

    driver_share_dir_1 = ament_index_python.packages.get_package_share_directory('velodyne_driver')
    driver_params_file_1 = os.path.join(driver_share_dir_1, 'config', 'vlp_1.yaml')
    velodyne_driver_node_1 = Node(
        package="velodyne_driver",
        executable="velodyne_driver_node",
        name="velodyne_driver_node_1",
        parameters=[driver_params_file_1],
        remappings=[
            ("velodyne_packets", "velodyne_packets_1")
        ]
    )

    convert_share_dir_1 = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
    convert_params_file_1 = os.path.join(convert_share_dir_1, 'config', 'VLP16-velodyne_convert_node-params.yaml')
    with open(convert_params_file_1, 'r') as f:
        convert_params_1 = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
    convert_params_1['calibration'] = os.path.join(convert_share_dir_1, 'params', 'VLP16db.yaml')
    velodyne_convert_node_1 = Node(
        package="velodyne_pointcloud",
        executable="velodyne_convert_node",
        name="velodyne_convert_node_1",
        parameters=[convert_params_1],
        remappings=[
            ("velodyne_packets", "velodyne_packets_1"),
            ("velodyne_points", "velodyne_points_1")
        ]
    )

    laserscan_share_dir_1 = ament_index_python.packages.get_package_share_directory('velodyne_laserscan')
    laserscan_params_file_1 = os.path.join(laserscan_share_dir_1, 'config', 'default-velodyne_laserscan_node-params.yaml')
    velodyne_laserscan_node_1 = Node(
        package="velodyne_laserscan",
        executable="velodyne_laserscan_node",
        name="velodyne_laserscan_node_1",
        parameters=[laserscan_params_file_1],
        remappings=[
            ("velodyne_points", "velodyne_points_1"),
            ("scan", "scan_1")
        ]
    )

    #velodyne_2
    driver_share_dir_2 = ament_index_python.packages.get_package_share_directory('velodyne_driver')
    driver_params_file_2 = os.path.join(driver_share_dir_2, 'config', 'vlp_1.yaml')
    velodyne_driver_node_2 = Node(
        package="velodyne_driver",
        executable="velodyne_driver_node",
        name="velodyne_driver_node_2",
        parameters=[driver_params_file_2],
        remappings=[
            ("velodyne_packets", "velodyne_packets_2")
        ]
    )

    convert_share_dir_2 = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
    convert_params_file_2 = os.path.join(convert_share_dir_2, 'config', 'VLP16-velodyne_convert_node-params.yaml')
    with open(convert_params_file_2, 'r') as f:
        convert_params_2 = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
    convert_params_2['calibration'] = os.path.join(convert_share_dir_2, 'params', 'VLP16db.yaml')
    velodyne_convert_node_2 = Node(
        package="velodyne_pointcloud",
        executable="velodyne_convert_node",
        name="velodyne_convert_node_2",
        parameters=[convert_params_2],
        remappings=[
            ("velodyne_packets", "velodyne_packets_2"),
            ("velodyne_points", "velodyne_points_2")
        ]
    )

    laserscan_share_dir_2 = ament_index_python.packages.get_package_share_directory('velodyne_laserscan')
    laserscan_params_file_2 = os.path.join(laserscan_share_dir_2, 'config', 'default-velodyne_laserscan_node-params.yaml')
    velodyne_laserscan_node_2 = Node(
        package="velodyne_laserscan",
        executable="velodyne_laserscan_node",
        name="velodyne_laserscan_node_2",
        parameters=[laserscan_params_file_2],
        remappings=[
            ("velodyne_points", "velodyne_points_2"),
            ("scan", "scan_2")
        ]
    )     

    ld.add_action(velodyne_driver_node_1)
    ld.add_action(velodyne_convert_node_1)
    ld.add_action(velodyne_laserscan_node_1)
    ld.add_action(velodyne_driver_node_2)
    ld.add_action(velodyne_convert_node_2)
    ld.add_action(velodyne_laserscan_node_2)
    return ld
edit flag offensive delete link more

Comments

The roboticsbackend link seems to be broken

abhishek47 gravatar image abhishek47  ( 2021-08-05 05:44:58 -0500 )edit

My friend,you can also refer to this link : https://docs.ros.org/en/foxy/Guides/L...

ylh gravatar image ylh  ( 2021-08-07 02:03:38 -0500 )edit

I have done similar modification on the launch file. However, the start log info of ros2 launch showing that the .yaml config actually not being loaded as expected, mine are 2 x VLP 16, but it loaded a 64E model with default port 2368.

ThomasL624 gravatar image ThomasL624  ( 2022-11-08 01:43:48 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-08-02 06:12:41 -0500

Seen: 782 times

Last updated: Aug 05 '21