We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Required Info:
from launch import LaunchDescription from launch.actions import GroupAction, RegisterEventHandler from launch.event_handlers import OnProcessStart from launch_ros.actions import LoadComposableNodes, Node, SetParameter from launch_ros.descriptions import ComposableNode def generate_launch_description(): # noqa: D103 container = Node( name="container", package="rclcpp_components", executable="component_container", output="screen", respawn=True, ) load_composable_nodes = LoadComposableNodes( target_container="container", composable_node_descriptions=[ ComposableNode( package="composition", plugin="composition::Talker", name="talker" ), ], ) event = RegisterEventHandler( OnProcessStart( target_action=container, on_start=[load_composable_nodes], ) ) bringup_cmd_group = GroupAction( actions=[ SetParameter("use_sim_time", True), container, # load_composable_nodes, # with this use_sim_time of the talker node is True event, # with this use_sim_time of the talker node is False ] ) ld = LaunchDescription() ld.add_action(bringup_cmd_group) return ld
ros2 param get /talker use_sim_time -> should yield True
ros2 param get /talker use_sim_time
ros2 param get /talker use_sim_time -> yields False
In case you are wondering why I need to do it like this, it's to workaround this issue
The text was updated successfully, but these errors were encountered:
I notice the same for SetEnvironmentVariable, it will also not propagate into the event handler callback
SetEnvironmentVariable
Sorry, something went wrong.
No branches or pull requests
Bug report
Required Info:
Steps to reproduce issue
Expected behavior
ros2 param get /talker use_sim_time
-> should yield TrueActual behavior
ros2 param get /talker use_sim_time
-> yields FalseAdditional information
In case you are wondering why I need to do it like this, it's to workaround this issue
The text was updated successfully, but these errors were encountered: