2
$\begingroup$

I've came across an interesting issue.

Is it possible to get the value of the LaunchArgument inside the python launch file?

Take the following scenario:

...
def generate_launch_description():

  input_topic_arg = DeclareLaunchArgument(name="input_topic", default_value=TextSubstitution(text=default_topic))

  --> get the "input_topic" launch argument string here somehow <--


  return LaunchDescription([
    input_topic_arg,
    Node(
      package='demo_package',
      executable='demo_node',
      output='screen',
      parameters=[{"input_topic": LaunchConfiguration('input_topic')}]
  ])

I've went through the LaunchArgument source code and found that is impossible to get the value directly from the input_topic_arg variable as the LaunchArgument code passes its default directly into LanchConfiguration.

That leaves us with only one option and that is forcing the value out of the LaunchConfiguration('input_topic') object. This class has a perform(LaunchContext) function that is designed to return the parameter value, but it requires the LaunchContext which was used in the launch file.

So the question is: Given this is the way to get to the LaunchArgument, is there a way of getting the implicitly defined Context which has been used to construct LaunchConfiguration?

$\endgroup$

1 Answer 1

0
$\begingroup$

I've accidentally stumbled upon an answer to this issue while reading the OpenVINS docs.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

launch_args = [
    DeclareLaunchArgument(name='config', default_value='default', description='description'),
]

def launch_setup(context):
    config = LaunchConfiguration('config').perform(context) # Here you'll get the runtime config value

    node1 = Node(package = '...',
                 executable = '...',
                 parameters =[{'config': LaunchConfiguration('config')}])

    return [node1]

def generate_launch_description():
    opfunc = OpaqueFunction(function = launch_setup)
    ld = LaunchDescription(launch_args)
    ld.add_action(opfunc)
    return ld

Basically you need to create an OpaqueFunction that recieves the correct runtime context -> This allows for correctly evaluating the LaunchConfiguration.perform(Context) function.

You can then act upon the runtime config value in whatever way you like.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.