Skip to content

Commit

Permalink
Log level (#3110)
Browse files Browse the repository at this point in the history
* added log level for navigation launch

* localization log level

* slam log level

* revert use_comp

* added log level to components
  • Loading branch information
jwallace42 authored and SteveMacenski committed Aug 24, 2022
1 parent 187f729 commit 9e83442
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 1 deletion.
7 changes: 7 additions & 0 deletions nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ def generate_launch_description():
autostart = LaunchConfiguration('autostart')
use_composition = LaunchConfiguration('use_composition')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')

# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
Expand Down Expand Up @@ -107,6 +108,10 @@ def generate_launch_description():
'use_respawn', default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.')

declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info',
description='log level')

# Specify the actions
bringup_cmd_group = GroupAction([
PushRosNamespace(
Expand All @@ -119,6 +124,7 @@ def generate_launch_description():
package='rclcpp_components',
executable='component_container_isolated',
parameters=[configured_params, {'autostart': autostart}],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings,
output='screen'),

Expand Down Expand Up @@ -171,6 +177,7 @@ def generate_launch_description():
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)

# Add the actions to launch all of the navigation nodes
ld.add_action(bringup_cmd_group)
Expand Down
9 changes: 9 additions & 0 deletions nav2_bringup/launch/localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ def generate_launch_description():
use_composition = LaunchConfiguration('use_composition')
container_name = LaunchConfiguration('container_name')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')

lifecycle_nodes = ['map_server', 'amcl']

Expand Down Expand Up @@ -99,6 +100,10 @@ def generate_launch_description():
'use_respawn', default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.')

declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info',
description='log level')

load_nodes = GroupAction(
condition=IfCondition(PythonExpression(['not ', use_composition])),
actions=[
Expand All @@ -110,6 +115,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_amcl',
Expand All @@ -119,12 +125,14 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_localization',
output='screen',
arguments=['--ros-args', '--log-level', log_level],
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': lifecycle_nodes}])
Expand Down Expand Up @@ -172,6 +180,7 @@ def generate_launch_description():
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_container_name_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)

# Add the actions to launch all of the localiztion nodes
ld.add_action(load_nodes)
Expand Down
15 changes: 14 additions & 1 deletion nav2_bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ def generate_launch_description():
use_composition = LaunchConfiguration('use_composition')
container_name = LaunchConfiguration('container_name')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')

lifecycle_nodes = ['controller_server',
'smoother_server',
Expand Down Expand Up @@ -100,6 +101,10 @@ def generate_launch_description():
'use_respawn', default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.')

declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info',
description='log level')

load_nodes = GroupAction(
condition=IfCondition(PythonExpression(['not ', use_composition])),
actions=[
Expand All @@ -110,6 +115,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
Node(
package='nav2_smoother',
Expand All @@ -119,6 +125,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_planner',
Expand All @@ -128,6 +135,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_behaviors',
Expand All @@ -137,6 +145,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_bt_navigator',
Expand All @@ -146,6 +155,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_waypoint_follower',
Expand All @@ -155,6 +165,7 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_velocity_smoother',
Expand All @@ -164,13 +175,15 @@ def generate_launch_description():
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_navigation',
output='screen',
arguments=['--ros-args', '--log-level', log_level],
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': lifecycle_nodes}]),
Expand Down Expand Up @@ -248,7 +261,7 @@ def generate_launch_description():
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_container_name_cmd)
ld.add_action(declare_use_respawn_cmd)

ld.add_action(declare_log_level_cmd)
# Add the actions to launch all of the navigation nodes
ld.add_action(load_nodes)
ld.add_action(load_composable_nodes)
Expand Down
8 changes: 8 additions & 0 deletions nav2_bringup/launch/slam_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
autostart = LaunchConfiguration('autostart')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')

# Variables
lifecycle_nodes = ['map_saver']
Expand Down Expand Up @@ -75,6 +76,10 @@ def generate_launch_description():
'use_respawn', default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.')

declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info',
description='log level')

# Nodes launching commands

start_map_saver_server_cmd = Node(
Expand All @@ -83,13 +88,15 @@ def generate_launch_description():
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
arguments=['--ros-args', '--log-level', log_level],
parameters=[configured_params])

start_lifecycle_manager_cmd = Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_slam',
output='screen',
arguments=['--ros-args', '--log-level', log_level],
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': lifecycle_nodes}])
Expand Down Expand Up @@ -119,6 +126,7 @@ def generate_launch_description():
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)

# Running Map Saver Server
ld.add_action(start_map_saver_server_cmd)
Expand Down

0 comments on commit 9e83442

Please sign in to comment.