It's automatically evaluated in the launch phase, so generally, you don't have to care about it.
If you'd like to print the value for debugging, you can use OpaqueFunction
.
Related: https://answers.ros.org/question/3226...
I put a minimal example here.
# false
$ ros2 launch sample.launch.py use_sim_time:=false
use_sim_time: false
$ ros2 param get /publisher use_sim_time
Boolean value is: False
# true
$ ros2 launch sample.launch.py use_sim_time:=true
use_sim_time: true
$ ros2 param get /publisher use_sim_time
Boolean value is: True
The launch file is:
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node, SetParameter
def launch_setup(context, *args, **kwargs):
use_sim_time = LaunchConfiguration("use_sim_time")
print(f"use_sim_time: {use_sim_time.perform(context)}")
set_use_sim_time = SetParameter(name="use_sim_time", value=use_sim_time)
node = Node(
package="examples_rclcpp_minimal_publisher",
executable="publisher_lambda",
name="publisher",
)
return [
set_use_sim_time,
node,
]
def generate_launch_description():
return LaunchDescription(
[
DeclareLaunchArgument("use_sim_time", default_value="false"),
OpaqueFunction(function=launch_setup),
]
)