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

IfCondition(PythonExpression()) - am I doing it right?

asked 2020-08-25 03:53:18 -0600

KenYN gravatar image

I'm trying to write a launch script to allow me to say ros2 launch foo.launch.py bag_full_path:=/v1_bags/foo.bag bag_version:=v1 and ros2 launch foo.launch.py bag_full_path:=/v2_bags/bar.bag bag_version:=v2, but the code I am getting is quite long-winded, so I suspect I am missing a trick or two. This code works, but is ugly:

Ros1BagPlayNode = launch.actions.ExecuteProcess(
    cmd=['ros2', 'bag', 'play', '-s', 'rosbag_v2', LaunchConfiguration('bag_full_path')],
    name='rosbag_play',
    output='log',
    condition=IfCondition(PythonExpression(["'", LaunchConfiguration('bag_version'), "' == 'v1'"]))
)
Ros2BagPlayNode = launch.actions.ExecuteProcess(
    cmd=['ros2', 'bag', 'play', LaunchConfiguration('bag_full_path')],
    name='rosbag_play',
    output='log',
    condition=IfCondition(PythonExpression(["'", LaunchConfiguration('bag_version'), "' == 'v2'"]))
)

DelayedRosBagPlayNode = launch.actions.TimerAction(
    actions = [Ros1BagPlayNode, Ros2BagPlayNode],
    period = 5.0 # Delay 5 seconds before launching
)

I know I could instead use is_v1_bag:=T/F and is_v2_bag:=T/F, but is there a neater way of testing strings?

BTW, the only other example of this I could find is this Japanese page so perhaps the official repo needs an extra example or two?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2020-08-25 05:22:20 -0600

lukicdarkoo gravatar image

It seems that a neater solution is on the way:
https://github.com/ros2/launch/pull/453

Once the PR changes are available upstream, you will be able to do something like:

import launch
from launch.actions import LogInfo, DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.conditions import LaunchConfigurationEquals


def generate_launch_description():
    return launch.LaunchDescription([
        DeclareLaunchArgument('bag_version', default_value='v1'),
        LogInfo(msg=LaunchConfiguration('bag_version')),
        LogInfo(msg='Version 1', condition=LaunchConfigurationEquals('bag_version', 'v1')),
        LogInfo(msg='Version 2', condition=LaunchConfigurationEquals('bag_version', 'v2'))
    ])

Before the LaunchConfigurationEqualscondition is available I guess your best bet is to copy the condition locally: https://github.com/ros2/launch/blob/m...
and change the import once it becomes available upstream.

Or, to stick with the solution you have now.

edit flag offensive delete link more

Comments

Thanks, that's a much nicer syntax!

KenYN gravatar image KenYN  ( 2020-08-25 05:34:34 -0600 )edit

Question Tools

4 followers

Stats

Asked: 2020-08-25 03:53:18 -0600

Seen: 3,291 times

Last updated: Aug 25 '20