Skip to content

Commit

Permalink
Do not import rclpy nor launch_ros at module level. (#69)
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic authored Sep 11, 2019
1 parent 897cae8 commit 5091afb
Showing 1 changed file with 2 additions and 3 deletions.
5 changes: 2 additions & 3 deletions launch_testing_ros/launch_testing_ros/test_runner.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,20 +15,19 @@
"""Module for a ROS aware LaunchTestRunner."""

import launch
import launch_ros
import launch_testing.test_runner

import rclpy


class LaunchTestRunner(launch_testing.test_runner.LaunchTestRunner):

def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
import rclpy # Import on first use to avoid races at module level
self._rclpy_context = rclpy.context.Context()
rclpy.init(args=self._launch_file_arguments, context=self._rclpy_context)

def generate_preamble(self):
import launch_ros # Import on first use to avoid races at module level
return [launch.actions.IncludeLaunchDescription(
launch_description_source=launch.LaunchDescriptionSource(
launch_description=launch_ros.get_default_launch_description(
Expand Down

0 comments on commit 5091afb

Please sign in to comment.