Skip to content

Commit

Permalink
test controller refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Jan 26, 2024
1 parent bfc344d commit 8292503
Show file tree
Hide file tree
Showing 6 changed files with 35 additions and 142 deletions.
20 changes: 4 additions & 16 deletions rosbot_xl_controller/test/test_diff_drive_controllers.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch.actions import IncludeLaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from test_utils import ControllersTestNode
from test_utils import ControllersTestNode, controller_test


@launch_pytest.fixture
Expand Down Expand Up @@ -82,25 +82,13 @@ def test_controllers_startup_fail():


@pytest.mark.launch(fixture=generate_test_description)
def test_controllers_startup_success():
def test_controllers_startup():
rclpy.init()
try:
node = ControllersTestNode("test_controllers_startup_success")
node = ControllersTestNode("test_controllers_startup")
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected JointStates message but it was not received. Check joint_state_broadcaster!"
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Odom message but it was not received. Check rosbot_xl_base_controller!"
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Imu message but it was not received. Check imu_broadcaster!"
controller_test(node)
finally:
rclpy.shutdown()
20 changes: 4 additions & 16 deletions rosbot_xl_controller/test/test_mecanum_controllers.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch.actions import IncludeLaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from test_utils import ControllersTestNode
from test_utils import ControllersTestNode, controller_test


@launch_pytest.fixture
Expand Down Expand Up @@ -82,25 +82,13 @@ def test_controllers_startup_fail():


@pytest.mark.launch(fixture=generate_test_description)
def test_controllers_startup_success():
def test_controllers_startup():
rclpy.init()
try:
node = ControllersTestNode("test_controllers_startup_success")
node = ControllersTestNode("test_controllers_startup")
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected JointStates message but it was not received. Check joint_state_broadcaster!"
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Odom message but it was not received. Check rosbot_xl_base_controller!"
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Imu message but it was not received. Check imu_broadcaster!"
controller_test(node)
finally:
rclpy.shutdown()
18 changes: 2 additions & 16 deletions rosbot_xl_controller/test/test_multirobot_controllers.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch.actions import IncludeLaunchDescription, TimerAction
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from test_utils import ControllersTestNode
from test_utils import ControllersTestNode, controller_test

robot_names = ["rosbot_xl1", "rosbot_xl2", "rosbot_xl3"]

Expand Down Expand Up @@ -71,21 +71,7 @@ def test_multirobot_controllers_startup_success():
node = ControllersTestNode(f"test_{robot_name}_controllers", namespace=robot_name)
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert msgs_received_flag, (
f"Expected JointStates message but it was not received. Check {robot_name}/"
"joint_state_broadcaster!"
)
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert msgs_received_flag, (
f"Expected Odom message but it was not received. Check {robot_name}/"
"rosbot_xl_base_controller!"
)
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), f"Expected Imu message but it was not received. Check {robot_name}/imu_broadcaster!"
controller_test(node, robot_name)
finally:
rclpy.shutdown()
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch.actions import IncludeLaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from test_utils import ControllersTestNode
from test_utils import ControllersTestNode, controller_test


@launch_pytest.fixture
Expand Down Expand Up @@ -56,56 +56,13 @@ def generate_test_description():


@pytest.mark.launch(fixture=generate_test_description)
def test_namespaced_controllers_startup_fail():
def test_namespaced_controllers_startup():
rclpy.init()
try:
node = ControllersTestNode(
"test_namespaced_controllers_startup_fail", namespace="rosbot_xl"
)
node.create_test_subscribers_and_publishers()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, (
"Received JointStates message that should not have appeared. Check whether other"
" robots are connected to your network.!"
)
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, (
"Received Odom message that should not have appeared. Check whether other robots are"
" connected to your network.!"
)
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, (
"Received Imu message that should not have appeared. Check whether other robots are"
" connected to your network.!"
)
finally:
rclpy.shutdown()


@pytest.mark.launch(fixture=generate_test_description)
def test_namespaced_controllers_startup_success():
rclpy.init()
try:
node = ControllersTestNode(
"test_namespaced_controllers_startup_success", namespace="rosbot_xl"
)
node = ControllersTestNode("test_namespaced_controllers_startup", namespace="rosbot_xl")
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected JointStates message but it was not received. Check joint_state_broadcaster!"
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Odom message but it was not received. Check rosbot_xl_base_controller!"
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Imu message but it was not received. Check imu_broadcaster!"
controller_test(node)
finally:
rclpy.shutdown()
51 changes: 4 additions & 47 deletions rosbot_xl_controller/test/test_namespaced_mecanum_controllers.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch.actions import IncludeLaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from test_utils import ControllersTestNode
from test_utils import ControllersTestNode, controller_test


@launch_pytest.fixture
Expand Down Expand Up @@ -56,56 +56,13 @@ def generate_test_description():


@pytest.mark.launch(fixture=generate_test_description)
def test_namespaced_controllers_startup_fail():
def test_namespaced_controllers_startup():
rclpy.init()
try:
node = ControllersTestNode(
"test_namespaced_controllers_startup_fail", namespace="rosbot_xl"
)
node.create_test_subscribers_and_publishers()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, (
"Received JointStates message that should not have appeared. Check whether other"
" robots are connected to your network.!"
)
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, (
"Received Odom message that should not have appeared. Check whether other robots are"
" connected to your network.!"
)
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, (
"Received Imu message that should not have appeared. Check whether other robots are"
" connected to your network.!"
)
finally:
rclpy.shutdown()


@pytest.mark.launch(fixture=generate_test_description)
def test_namespaced_controllers_startup_success():
rclpy.init()
try:
node = ControllersTestNode(
"test_namespaced_controllers_startup_success", namespace="rosbot_xl"
)
node = ControllersTestNode("test_namespaced_controllers_startup", namespace="rosbot_xl")
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected JointStates message but it was not received. Check joint_state_broadcaster!"
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Odom message but it was not received. Check rosbot_xl_base_controller!"
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Imu message but it was not received. Check imu_broadcaster!"
controller_test(node)
finally:
rclpy.shutdown()
17 changes: 17 additions & 0 deletions rosbot_xl_controller/test/test_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,3 +91,20 @@ def publish_fake_hardware_messages(self):

self.imu_publisher.publish(imu_msg)
self.joint_states_publisher.publish(joint_state_msg)


def controller_test(node, robot_name="ROSbot"):
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert msgs_received_flag, (
f"{robot_name}: Expected JointStates message but it was not received. Check "
"joint_state_broadcaster!"
)
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert msgs_received_flag, (
f"{robot_name}: Expected Odom message but it was not received. Check "
"rosbot_xl_base_controller!"
)
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
assert (
msgs_received_flag
), f"{robot_name}: Expected Imu message but it was not received. Check imu_broadcaster!"

0 comments on commit 8292503

Please sign in to comment.