Skip to content

Commit

Permalink
change class name
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Jan 30, 2024
1 parent a2ccc35 commit e72275d
Show file tree
Hide file tree
Showing 8 changed files with 20 additions and 19 deletions.
1 change: 1 addition & 0 deletions industrial_ci
Submodule industrial_ci added at c2b7b6
4 changes: 2 additions & 2 deletions rosbot_xl_gazebo/test/test_diff_drive_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.actions import ReadyToTest
from launch_testing.util import KeepAliveProc
from test_utils import SimulationTest, diff_test
from test_utils import SimulationTestNode, diff_test
from test_ign_kill_utils import kill_ign_linux_processes
from threading import Thread

Expand Down Expand Up @@ -71,7 +71,7 @@ def generate_test_description():
def test_diff_drive_simulation():
rclpy.init()
try:
node = SimulationTest("test_diff_drive_simulation")
node = SimulationTestNode("test_diff_drive_simulation")
Thread(target=lambda node: rclpy.spin(node), args=(node,)).start()

diff_test(node)
Expand Down
4 changes: 2 additions & 2 deletions rosbot_xl_gazebo/test/test_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.actions import ReadyToTest
from launch_testing.util import KeepAliveProc
from test_utils import SimulationTest, mecanum_test
from test_utils import SimulationTestNode, mecanum_test
from test_ign_kill_utils import kill_ign_linux_processes
from threading import Thread

Expand Down Expand Up @@ -72,7 +72,7 @@ def generate_test_description():
def test_mecanum_simulation():
rclpy.init()
try:
node = SimulationTest("test_mecanum_simulation")
node = SimulationTestNode("test_mecanum_simulation")
Thread(target=lambda node: rclpy.spin(node), args=(node,)).start()

mecanum_test(node)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
from launch_testing.actions import ReadyToTest
from launch_testing.util import KeepAliveProc
from rclpy.executors import SingleThreadedExecutor
from test_utils import SimulationTest, diff_test
from test_utils import SimulationTestNode, diff_test
from test_ign_kill_utils import kill_ign_linux_processes
from threading import Thread

Expand Down Expand Up @@ -68,7 +68,7 @@ def test_multirobot_diff_drive_simulation():
executor = SingleThreadedExecutor()

for node_namespace in robots:
node = SimulationTest("test_multirobot_diff_drive_simulation", namespace=node_namespace)
node = SimulationTestNode("test_multirobot_diff_drive_simulation", namespace=node_namespace)
nodes[node_namespace] = node
executor.add_node(node)

Expand Down
4 changes: 2 additions & 2 deletions rosbot_xl_gazebo/test/test_multirobot_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
from launch_testing.actions import ReadyToTest
from launch_testing.util import KeepAliveProc
from rclpy.executors import SingleThreadedExecutor
from test_utils import SimulationTest, mecanum_test
from test_utils import SimulationTestNode, mecanum_test
from test_ign_kill_utils import kill_ign_linux_processes
from threading import Thread

Expand Down Expand Up @@ -69,7 +69,7 @@ def test_multirobot_mecanum_simulation():
executor = SingleThreadedExecutor()

for node_namespace in robots:
node = SimulationTest("test_multirobot_mecanum_simulation", namespace=node_namespace)
node = SimulationTestNode("test_multirobot_mecanum_simulation", namespace=node_namespace)
nodes[node_namespace] = node
executor.add_node(node)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.actions import ReadyToTest
from launch_testing.util import KeepAliveProc
from test_utils import SimulationTest, diff_test
from test_utils import SimulationTestNode, diff_test
from test_ign_kill_utils import kill_ign_linux_processes
from threading import Thread

Expand Down Expand Up @@ -73,7 +73,7 @@ def generate_test_description():
def test_namespaced_diff_drive_simulation():
rclpy.init()
try:
node = SimulationTest("test_namespaced_diff_drive_simulation", namespace="rosbot_xl")
node = SimulationTestNode("test_namespaced_diff_drive_simulation", namespace="rosbot_xl")
Thread(target=lambda node: rclpy.spin(node), args=(node,)).start()

diff_test(node)
Expand Down
4 changes: 2 additions & 2 deletions rosbot_xl_gazebo/test/test_namespaced_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.actions import ReadyToTest
from launch_testing.util import KeepAliveProc
from test_utils import SimulationTest, mecanum_test
from test_utils import SimulationTestNode, mecanum_test
from test_ign_kill_utils import kill_ign_linux_processes
from threading import Thread

Expand Down Expand Up @@ -72,7 +72,7 @@ def generate_test_description():
def test_namespaced_mecanum_simulation():
rclpy.init()
try:
node = SimulationTest("test_namespaced_mecanum_simulation", namespace="rosbot_xl")
node = SimulationTestNode("test_namespaced_mecanum_simulation", namespace="rosbot_xl")
Thread(target=lambda node: rclpy.spin(node), args=(node,)).start()

mecanum_test(node)
Expand Down
14 changes: 7 additions & 7 deletions rosbot_xl_gazebo/test/test_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
from sensor_msgs.msg import LaserScan, Image, Imu, JointState, PointCloud2


class SimulationTest(Node):
class SimulationTestNode(Node):
__test__ = False

# The inaccuracies in measurement uncertainties and wheel slippage
Expand Down Expand Up @@ -186,11 +186,11 @@ def __exit__(self, exep_type, exep_value, trace):
self.shutdown()


def wait_for_initialization(node: SimulationTest, robot_name="ROSbot"):
def wait_for_initialization(node: SimulationTestNode, robot_name="ROSbot"):
assert node.robot_initialized_event.wait(30), f"{robot_name} does not initialized correctly!"


def x_speed_test(node: SimulationTest, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="ROSbot"):
def x_speed_test(node: SimulationTestNode, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="ROSbot"):
node.set_destination_speed(v_x, v_y, v_yaw)
# node.rate.sleep()
assert node.vel_stabilization_time_event.wait(20.0), (
Expand All @@ -209,7 +209,7 @@ def x_speed_test(node: SimulationTest, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="
)


def y_speed_test(node: SimulationTest, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="ROSbot"):
def y_speed_test(node: SimulationTestNode, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="ROSbot"):
node.set_destination_speed(v_x, v_y, v_yaw)

assert node.vel_stabilization_time_event.wait(20.0), (
Expand All @@ -228,7 +228,7 @@ def y_speed_test(node: SimulationTest, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="
)


def yaw_speed_test(node: SimulationTest, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="ROSbot"):
def yaw_speed_test(node: SimulationTestNode, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name="ROSbot"):
node.set_destination_speed(v_x, v_y, v_yaw)

assert node.vel_stabilization_time_event.wait(20.0), (
Expand All @@ -246,15 +246,15 @@ def yaw_speed_test(node: SimulationTest, v_x=0.0, v_y=0.0, v_yaw=0.0, robot_name
), f"{robot_name} does not rotate properly. Check ekf_filter_node! Twist: {node.ekf_twist}"


def diff_test(node: SimulationTest, robot_name="ROSbot"):
def diff_test(node: SimulationTestNode, robot_name="ROSbot"):
wait_for_initialization(node, robot_name)
# 0.8 m/s and 3.14 rad/s are controller's limits defined in
# rosbot_xl_controller/config/mecanum_drive_controller.yaml
x_speed_test(node, v_x=0.8, robot_name=robot_name)
yaw_speed_test(node, v_yaw=3.14, robot_name=robot_name)


def mecanum_test(node: SimulationTest, robot_name="ROSbot"):
def mecanum_test(node: SimulationTestNode, robot_name="ROSbot"):
wait_for_initialization(node, robot_name)
# 0.8 m/s and 3.14 rad/s are controller's limits defined in
# rosbot_xl_controller/config/mecanum_drive_controller.yaml
Expand Down

0 comments on commit e72275d

Please sign in to comment.