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

How to pass launch args dynamically during launch-time

asked 2021-04-23 03:55:23 -0500

mamado gravatar image

updated 2023-04-28 13:22:04 -0500

130s gravatar image

I have a launch file that launch 2 ROS2 nodes for each vehicle(uav) I have. I would like to specify the number of vehicles I have while running the launch file so that the correct number of nodes is initialized.

My launch file looks like this:

import os
from time import sleep

from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from ament_index_python.packages import get_package_share_directory


launch_path = os.path.realpath(__file__).replace("demo.launch.py", "")
ros2_ws = os.path.realpath(os.path.relpath(os.path.join(launch_path,"../../../../..")))

avoidance_path = os.path.join(ros2_ws,"src","avoidance")
avoidance_config_path = os.path.join(avoidance_path,"config")

number_of_uavs = int(input("how many uavs do you want to simulate? "))

def generate_launch_description():

    ld = LaunchDescription()

    for i in range(1, number_of_uavs+1):
        namespace="uav_{:s}".format(str(i))

        config = os.path.join(
        avoidance_config_path,
        namespace,
        "params.yaml"
        )

        avoidance_node = Node(
            package="avoidance",
            namespace=namespace,
            executable="avoidance_client_1",
            output="screen",
            parameters=[config]

        )

        trajectory_controller_node = Node(
            package="offboard_exp",
            namespace=namespace,
            executable="trajectory_controller",
            name="trajectory_controller_{:s}".format(namespace)
        )

        ld.add_action(trajectory_controller_node)
        ld.add_action(avoidance_node)

    return ld

Currently, I use number_of_uavs = int(input("how many uavs do you want to simulate? ")) To get the number of vehicles and then change the namespace of the node in each iteration.

Is there a better way to pass this parameter instead of prompting the user to enter it?

edit retag flag offensive close merge delete

Comments

IIUC, you're asking for a better option than (statically) passing arg upon execution (e.g. via cmdline). But in the subject you said "how to pass command args", which contradicts to what you're asking in the question body. I modified the subject to try to describe what you really want.

130s gravatar image 130s  ( 2023-04-28 13:24:16 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
3

answered 2021-04-23 16:16:07 -0500

sgvandijk gravatar image

updated 2021-04-23 16:17:53 -0500

I am not sure if it's better, but you could use sys.argv:

import sys

for arg in sys.argv:
    if arg.startswith("number_of_uavs:=")
        number_of_uavs = int(arg.split(":=")[1])

With this, the command suggested without explanation by @avzmpy works:

ros2 launch PKG_NAME LAUNCH_FILE number_of_uavs:=NUMBER

There is probably a prettier way to parse the argument :) You do have to use the := notation, because ros2 launch does not let any other through.


Having said this, this is not how I would do what you want to do, to launch multiple identical UAVs. I would limit the launch file to launch a single UAV, with a launch argument declared to pass the UAV ID, and a LaunchConfiguration using it. Then I would create another wrapper (bash) script around it that does the loop and calls ros2 launch multiple times to launch the required number of UAVs. When done that way, you can also launch each with a different value of ROS_DOMAIN_ID to make it impossible for them to mix communication without needing to use namespaces.

edit flag offensive delete link more
1

answered 2021-04-23 04:52:16 -0500

abhishek47 gravatar image

updated 2021-04-24 00:45:13 -0500

DeclareLaunchArgument can be used for this (which your code already imports btw). You could do:

number_of_uavs = DeclareLaunchArgument('number_of_uavs', default_value=1)

Check out the answer to What is different between DeclareLaunchArgument and LaunchConfiguration.


Also make note of @sgvandijk's comment and his answer.

edit flag offensive delete link more

Comments

3

I don't think this is the right answer: the value that is given for the launch argument is only available in the launch configuration at execution time of the launch description, you can't use the value while _building_ the description. So I don't believe you would be able to use it in a for-loop to add actions to the launch description, like in the original question. You must use it combined with a LaunchConfiguration substitution as described in the answer that you linked.

Separately, AFAICT you can't use an integer value for the default value of a launch argument, it has to be a string or a substitution.

sgvandijk gravatar image sgvandijk  ( 2021-04-23 15:51:22 -0500 )edit
0

answered 2021-04-23 08:16:28 -0500

avzmpy gravatar image

updated 2021-04-23 08:16:46 -0500

ros2 launch PKG_NAME LAUNCH_FILE number_of_uavs:=NUMBER

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2021-04-23 03:55:23 -0500

Seen: 9,288 times

Last updated: Apr 28 '23