Skip to content

Commit

Permalink
Fix misleading deprecated warnings when using launch arguments
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno committed Dec 12, 2019
1 parent d6dd5c0 commit 8fae305
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 6 deletions.
5 changes: 3 additions & 2 deletions launch_ros/launch_ros/default_launch_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,12 @@
class ROSSpecificLaunchStartup(launch.actions.OpaqueFunction):
"""Does ROS specific launch startup."""

def __init__(self, rclpy_context=None):
def __init__(self, rclpy_context=None, argv=None):
"""Create a ROSSpecificLaunchStartup opaque function."""
super().__init__(function=self._function)
self.__shutting_down = False
self.__rclpy_context = rclpy_context
self.__argv = None

def _shutdown(self, event: launch.Event, context: launch.LaunchContext):
self.__shutting_down = True
Expand All @@ -57,7 +58,7 @@ def _function(self, context: launch.LaunchContext):
try:
if self.__rclpy_context is None:
# Initialize the default global context
rclpy.init(args=context.argv)
rclpy.init(args=self.__argv)
except RuntimeError as exc:
if 'rcl_init called while already initialized' in str(exc):
pass
Expand Down
2 changes: 1 addition & 1 deletion ros2launch/ros2launch/api/api.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ def launch_a_launch_file(*, launch_file_path, launch_file_arguments, debug=False
"""Launch a given launch file (by path) and pass it the given launch file arguments."""
launch_service = launch.LaunchService(argv=launch_file_arguments, debug=debug)
context = rclpy.context.Context()
rclpy.init(args=launch_file_arguments, context=context)
rclpy.init(args=[], context=context)
launch_service.include_launch_description(
launch_ros.get_default_launch_description(
rclpy_context=context,
Expand Down
3 changes: 0 additions & 3 deletions ros2launch/ros2launch/command/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,6 @@ def add_arguments(self, parser, cli_name):
nargs='*',
help="Arguments to the launch file; '<name>:=<value>' (for duplicates, last one wins)")
arg.completer = LaunchFileNameCompleter()
parser.add_argument(
'argv', nargs=REMAINDER,
help='Pass arbitrary arguments to the launch file')

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

0 comments on commit 8fae305

Please sign in to comment.