Skip to content

Commit

Permalink
Address review comments
Browse files Browse the repository at this point in the history
  • Loading branch information
Pete Baughman committed Mar 6, 2019
1 parent a6d87b3 commit f0ebd90
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 5 deletions.
9 changes: 6 additions & 3 deletions launch_ros/launch_ros/default_launch_description.py
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,9 @@ def _run(self):

def _function(self, context: launch.LaunchContext):
try:
rclpy.init(args=context.argv, context=self.__rclpy_context)
if self.__rclpy_context is None:
# Initialize the default global context
rclpy.init(args=context.argv)
except RuntimeError as exc:
if 'rcl_init called while already initialized' in str(exc):
pass
Expand All @@ -121,8 +123,9 @@ def get_default_launch_description(*, prefix_output_with_name=False, rclpy_conte
with the name of the process as `[process_name] `, else it is printed
unmodified
:param: rclpy_context Provide a context other than the default rclpy context pass down
to rclpy.init
:param: rclpy_context Provide a context other than the default rclpy context to pass down
to rclpy.init. The context is expected to have already been initialized by the caller using
rclpy.init
"""
default_ros_launch_description = launch.LaunchDescription([
# ROS initialization (create node and other stuff).
Expand Down
14 changes: 12 additions & 2 deletions ros2launch/ros2launch/api/api.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
from launch.launch_description_sources import InvalidPythonLaunchFileError
from launch.launch_description_sources import load_python_launch_file_as_module
import launch_ros
import rclpy
import rclpy.context

# forward functions into this module's default namespace (useful for some autocompletion tools)
get_launch_description_from_python_launch_file = get_launch_description_from_python_launch_file
Expand Down Expand Up @@ -137,8 +139,14 @@ def parse_launch_arguments(launch_arguments: List[Text]) -> List[Tuple[Text, Tex
def launch_a_python_launch_file(*, python_launch_file_path, launch_file_arguments, debug=False):
"""Launch a given Python 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)
launch_service.include_launch_description(
launch_ros.get_default_launch_description(prefix_output_with_name=False))
launch_ros.get_default_launch_description(
prefix_output_with_name=False,
rclpy_context=context,
)
)
parsed_launch_arguments = parse_launch_arguments(launch_file_arguments)
# Include the user provided launch file using IncludeLaunchDescription so that the
# location of the current launch file is set.
Expand All @@ -151,7 +159,9 @@ def launch_a_python_launch_file(*, python_launch_file_path, launch_file_argument
),
])
launch_service.include_launch_description(launch_description)
return launch_service.run()
ret = launch_service.run()
context = rclpy.shutdown(context=context)
return ret


class LaunchFileNameCompleter:
Expand Down

0 comments on commit f0ebd90

Please sign in to comment.