Skip to content

Commit

Permalink
add severity level launch argument
Browse files Browse the repository at this point in the history
* rviz severity is hardcoded to WARN
* movegroup severity default is INFO
  • Loading branch information
Nibanovic committed Apr 5, 2024
1 parent bcbff4f commit 5c6c05a
Showing 1 changed file with 11 additions and 1 deletion.
12 changes: 11 additions & 1 deletion myrobot_ws/src/myrobot_moveit/launch/moveit.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ def launch_setup(context, *args, **kwargs):
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
use_sim_time = LaunchConfiguration("use_sim_time")
logging_severity = LaunchConfiguration("severity")

# -------------------------------------------------------#
# MoveIt2 MoveGroup setup #
Expand Down Expand Up @@ -68,6 +69,7 @@ def launch_setup(context, *args, **kwargs):
package="moveit_ros_move_group",
executable="move_group",
output="screen",
arguments=["--ros-args", "--log-level", logging_severity],
parameters=[
robot_description,
robot_description_semantic,
Expand All @@ -84,7 +86,7 @@ def launch_setup(context, *args, **kwargs):
package="rviz2",
executable="rviz2",
output="log",
arguments=["-d", rviz_config],
arguments=["-d", rviz_config, "--ros-args", "--log-level", "WARN"],
parameters=[
robot_description,
robot_description_semantic,
Expand Down Expand Up @@ -166,6 +168,14 @@ def generate_launch_description():
description="Use simulation clock instead of world clock",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"severity",
default_value="INFO",
choices=["INFO", "WARN", "ERROR", "DEBUG", "FATAL"],
description="Logging level for the nodes",
)
)

return LaunchDescription(
declared_arguments + [OpaqueFunction(function=launch_setup)]
Expand Down

0 comments on commit 5c6c05a

Please sign in to comment.