Skip to content

Commit

Permalink
Use class methods for rclpy.init/shutdown
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 15, 2024
1 parent dadaedd commit 10c1868
Show file tree
Hide file tree
Showing 17 changed files with 153 additions and 75 deletions.
23 changes: 16 additions & 7 deletions example_1/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -68,14 +67,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand All @@ -91,14 +95,19 @@ def test_check_if_msgs_published(self):


class TestFixtureCLI(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_main(self, proc_output):

Expand Down
12 changes: 8 additions & 4 deletions example_1/test/test_rrbot_launch_cli_direct.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import check_controllers_running


Expand All @@ -62,14 +61,19 @@ def generate_test_description():


class TestFixtureCliDirect(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_main(self, proc_output):

Expand Down
12 changes: 8 additions & 4 deletions example_10/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
from launch_testing.actions import ReadyToTest

import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand Down Expand Up @@ -68,14 +67,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
12 changes: 8 additions & 4 deletions example_11/test/test_carlikebot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -67,14 +66,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
25 changes: 17 additions & 8 deletions example_12/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -68,14 +67,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand All @@ -97,10 +101,9 @@ def test_check_if_msgs_published(self):
# This is our second test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixtureChained(unittest.TestCase):

def setUp(self):
@classmethod
def setUpClass(cls):
rclpy.init()
self.node = Node("test_node")
# Command to run the launch file
command = [
"ros2",
Expand All @@ -111,9 +114,15 @@ def setUp(self):
# Execute the command
subprocess.run(command)

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
12 changes: 8 additions & 4 deletions example_13/test/test_three_robots_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -68,14 +67,19 @@ def generate_test_description():
# This is our first test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -67,14 +66,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
12 changes: 8 additions & 4 deletions example_15/test/test_multi_controller_manager_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -67,14 +66,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
12 changes: 8 additions & 4 deletions example_15/test/test_rrbot_namespace_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -67,14 +66,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
12 changes: 8 additions & 4 deletions example_2/test/test_diffbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -67,14 +66,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
12 changes: 8 additions & 4 deletions example_3/test/test_rrbot_system_multi_interface_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

# import launch_testing.markers
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
Expand All @@ -67,14 +66,19 @@ def generate_test_description():
# This is our test fixture. Each method is a test case.
# These run alongside the processes specified in generate_test_description()
class TestFixture(unittest.TestCase):
@classmethod
def setUpClass(cls):
rclpy.init()

@classmethod
def tearDownClass(cls):
rclpy.shutdown()

def setUp(self):
rclpy.init()
self.node = Node("test_node")
self.node = rclpy.create_node("test_node")

def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def test_node_start(self, proc_output):
check_node_running(self.node, "robot_state_publisher")
Expand Down
Loading

0 comments on commit 10c1868

Please sign in to comment.