Skip to content

Commit 35c84cb

Browse files
authored
Fix misleading deprecated warnings when using launch arguments (#106)
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent d6dd5c0 commit 35c84cb

File tree

3 files changed

+4
-6
lines changed

3 files changed

+4
-6
lines changed

launch_ros/launch_ros/default_launch_description.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,11 +28,12 @@
2828
class ROSSpecificLaunchStartup(launch.actions.OpaqueFunction):
2929
"""Does ROS specific launch startup."""
3030

31-
def __init__(self, rclpy_context=None):
31+
def __init__(self, rclpy_context=None, argv=None):
3232
"""Create a ROSSpecificLaunchStartup opaque function."""
3333
super().__init__(function=self._function)
3434
self.__shutting_down = False
3535
self.__rclpy_context = rclpy_context
36+
self.__argv = None
3637

3738
def _shutdown(self, event: launch.Event, context: launch.LaunchContext):
3839
self.__shutting_down = True
@@ -57,7 +58,7 @@ def _function(self, context: launch.LaunchContext):
5758
try:
5859
if self.__rclpy_context is None:
5960
# Initialize the default global context
60-
rclpy.init(args=context.argv)
61+
rclpy.init(args=self.__argv)
6162
except RuntimeError as exc:
6263
if 'rcl_init called while already initialized' in str(exc):
6364
pass

ros2launch/ros2launch/api/api.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ def launch_a_launch_file(*, launch_file_path, launch_file_arguments, debug=False
141141
"""Launch a given launch file (by path) and pass it the given launch file arguments."""
142142
launch_service = launch.LaunchService(argv=launch_file_arguments, debug=debug)
143143
context = rclpy.context.Context()
144-
rclpy.init(args=launch_file_arguments, context=context)
144+
rclpy.init(args=[], context=context)
145145
launch_service.include_launch_description(
146146
launch_ros.get_default_launch_description(
147147
rclpy_context=context,

ros2launch/ros2launch/command/launch.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,9 +61,6 @@ def add_arguments(self, parser, cli_name):
6161
nargs='*',
6262
help="Arguments to the launch file; '<name>:=<value>' (for duplicates, last one wins)")
6363
arg.completer = LaunchFileNameCompleter()
64-
parser.add_argument(
65-
'argv', nargs=REMAINDER,
66-
help='Pass arbitrary arguments to the launch file')
6764

6865
def main(self, *, parser, args):
6966
"""Entry point for CLI program."""

0 commit comments

Comments
 (0)