-
Notifications
You must be signed in to change notification settings - Fork 1.6k
use_sim_time refactoring #3131
New issue
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
use_sim_time refactoring #3131
Changes from 8 commits
c73b0b3
2ed939b
518a7b6
eb2482b
47c5846
48b1c81
34b951f
60b84a1
1fcd63b
e5564d4
ef4adc4
2554851
6281bcf
262dee8
971d4be
fb11fb3
868a03e
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -20,7 +20,7 @@ | |
| from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable | ||
| from launch.conditions import IfCondition | ||
| from launch.substitutions import LaunchConfiguration, PythonExpression | ||
| from launch_ros.actions import LoadComposableNodes | ||
| from launch_ros.actions import LoadComposableNodes, SetParameter | ||
| from launch_ros.actions import Node | ||
| from launch_ros.descriptions import ComposableNode | ||
| from nav2_common.launch import RewrittenYaml | ||
|
|
@@ -52,7 +52,6 @@ def generate_launch_description(): | |
|
|
||
| # Create our own temporary YAML files that include substitutions | ||
| param_substitutions = { | ||
| 'use_sim_time': use_sim_time, | ||
| 'yaml_filename': map_yaml_file} | ||
|
|
||
| configured_params = RewrittenYaml( | ||
|
|
@@ -102,6 +101,7 @@ def generate_launch_description(): | |
| load_nodes = GroupAction( | ||
| condition=IfCondition(PythonExpression(['not ', use_composition])), | ||
| actions=[ | ||
| SetParameter("use_sim_time", use_sim_time), | ||
SteveMacenski marked this conversation as resolved.
Show resolved
Hide resolved
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. does SetParameter work globally or can it be used for a single node? Also, does that work if the parameter in question is inside of the yaml file also (clearly it works if its not inside the yaml file)? I ask because this could be a really nice solution for the
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It would be great not to require users to set In general though, that's a problem with this PR if it doesn't work with the param in the yaml too, since users' yaml files right now will have it from previous clones they're working under
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
It applies the parameter for all nodes within the GroupAction. See here
yes, the parameter in the yaml would override For the refactoring of
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Totally understood, just asking the question, it sounds like this would be a solution for it too. Duly noted.
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Leaving this un-resolved as a reminder to myself |
||
| Node( | ||
| package='nav2_map_server', | ||
| executable='map_server', | ||
|
|
@@ -125,37 +125,40 @@ def generate_launch_description(): | |
| executable='lifecycle_manager', | ||
| name='lifecycle_manager_localization', | ||
| output='screen', | ||
| parameters=[{'use_sim_time': use_sim_time}, | ||
| {'autostart': autostart}, | ||
| parameters=[{'autostart': autostart}, | ||
| {'node_names': lifecycle_nodes}]) | ||
| ] | ||
| ) | ||
|
|
||
| load_composable_nodes = LoadComposableNodes( | ||
| load_composable_nodes = GroupAction( | ||
| condition=IfCondition(use_composition), | ||
SteveMacenski marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| target_container=container_name, | ||
| composable_node_descriptions=[ | ||
| ComposableNode( | ||
| package='nav2_map_server', | ||
| plugin='nav2_map_server::MapServer', | ||
| name='map_server', | ||
| parameters=[configured_params], | ||
| remappings=remappings), | ||
| ComposableNode( | ||
| package='nav2_amcl', | ||
| plugin='nav2_amcl::AmclNode', | ||
| name='amcl', | ||
| parameters=[configured_params], | ||
| remappings=remappings), | ||
| ComposableNode( | ||
| package='nav2_lifecycle_manager', | ||
| plugin='nav2_lifecycle_manager::LifecycleManager', | ||
| name='lifecycle_manager_localization', | ||
| parameters=[{'use_sim_time': use_sim_time, | ||
| 'autostart': autostart, | ||
| 'node_names': lifecycle_nodes}]), | ||
| ], | ||
| ) | ||
| actions=[ | ||
| SetParameter("use_sim_time", use_sim_time), | ||
| LoadComposableNodes( | ||
| target_container=container_name, | ||
| composable_node_descriptions=[ | ||
| ComposableNode( | ||
| package='nav2_map_server', | ||
| plugin='nav2_map_server::MapServer', | ||
| name='map_server', | ||
| parameters=[configured_params], | ||
| remappings=remappings), | ||
| ComposableNode( | ||
| package='nav2_amcl', | ||
| plugin='nav2_amcl::AmclNode', | ||
| name='amcl', | ||
| parameters=[configured_params], | ||
| remappings=remappings), | ||
| ComposableNode( | ||
| package='nav2_lifecycle_manager', | ||
| plugin='nav2_lifecycle_manager::LifecycleManager', | ||
| name='lifecycle_manager_localization', | ||
| parameters=[{'autostart': autostart, | ||
| 'node_names': lifecycle_nodes}]), | ||
| ], | ||
| ) | ||
| ] | ||
| ) | ||
|
|
||
| # Create the launch description and populate | ||
| ld = LaunchDescription() | ||
|
|
||
Uh oh!
There was an error while loading. Please reload this page.