Skip to content

Commit

Permalink
Reuse check_node_running
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jul 29, 2024
1 parent 1351f95 commit cbc5015
Show file tree
Hide file tree
Showing 16 changed files with 101 additions and 128 deletions.
14 changes: 6 additions & 8 deletions example_1/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -74,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
14 changes: 6 additions & 8 deletions example_10/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
import launch_testing
import rclpy
from rclpy.node import Node
from ros2_control_demo_testing.test_utils import check_controllers_running, check_if_js_published
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# This function specifies the processes to be run for our test
Expand Down Expand Up @@ -79,12 +82,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
14 changes: 6 additions & 8 deletions example_11/test/test_carlikebot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -74,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
21 changes: 7 additions & 14 deletions example_12/test/test_rrbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time
import subprocess

from ament_index_python.packages import get_package_share_directory
Expand All @@ -43,7 +42,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -75,12 +78,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down Expand Up @@ -118,12 +116,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -74,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
15 changes: 6 additions & 9 deletions example_15/test/test_multi_controller_manager_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,8 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -75,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running_cm1(self, proc_output):

Expand Down
15 changes: 6 additions & 9 deletions example_15/test/test_rrbot_namespace_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,8 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -75,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
14 changes: 6 additions & 8 deletions example_2/test/test_diffbot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -74,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
14 changes: 6 additions & 8 deletions example_3/test/test_rrbot_system_multi_interface_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -74,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
14 changes: 6 additions & 8 deletions example_4/test/test_rrbot_system_with_sensor_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
Expand All @@ -42,7 +41,11 @@
# 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
from ros2_control_demo_testing.test_utils import (
check_controllers_running,
check_if_js_published,
check_node_running,
)


# Executes the given launch file and checks if all nodes can be started
Expand Down Expand Up @@ -74,12 +77,7 @@ def tearDown(self):
rclpy.shutdown()

def test_node_start(self, proc_output):
start = time.time()
found = False
while time.time() - start < 5.0 and not found:
found = "robot_state_publisher" in self.node.get_node_names()
time.sleep(0.1)
assert found, "robot_state_publisher not found!"
check_node_running(self.node, "robot_state_publisher")

def test_controller_running(self, proc_output):

Expand Down
Loading

0 comments on commit cbc5015

Please sign in to comment.