Skip to content

Commit

Permalink
add delayed controller launch
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Jan 30, 2024
1 parent f0ff7c1 commit 0be0c3a
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 20 deletions.
9 changes: 5 additions & 4 deletions rosbot_controller/test/test_multirobot_controllers.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,10 @@
import pytest
import rclpy


from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.actions import IncludeLaunchDescription, TimerAction
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from test_utils import ControllersTestNode, controller_readings_test
Expand All @@ -46,12 +47,13 @@ def generate_test_description():
launch_arguments={
"use_sim": "False",
"mecanum": "True",
"use_gpu": "False",
"namespace": robot_names[i],
}.items(),
)

actions.append(controller_launch)
# When there is no delay the controllers doesn't spawn correctly
delayed_controller_launch = TimerAction(period=i * 2.0, actions=[controller_launch])
actions.append(delayed_controller_launch)

return LaunchDescription(actions)

Expand All @@ -66,7 +68,6 @@ def test_multirobot_controllers_startup_success():
node.start_publishing_fake_hardware()

node.start_node_thread()

controller_readings_test(node, robot_name)
finally:
rclpy.shutdown()
30 changes: 14 additions & 16 deletions rosbot_controller/test/test_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,7 @@

from threading import Event
from threading import Thread

from rclpy.node import Node

from sensor_msgs.msg import JointState, Imu
from nav_msgs.msg import Odometry

Expand All @@ -46,10 +44,10 @@ def create_test_subscribers_and_publishers(self):

self.imu_sub = self.create_subscription(Imu, "imu_broadcaster/imu", self.imu_callback, 10)

# TODO: @delipl namespaces have not been implemented in microros yet
self.imu_publisher = self.create_publisher(Imu, "/_imu/data_raw", 10)
# TODO: @delihus namespaces have not been implemented in microros yet
self.imu_pub = self.create_publisher(Imu, "/_imu/data_raw", 10)

self.joint_states_publisher = self.create_publisher(JointState, "/_motors_response", 10)
self.joint_pub = self.create_publisher(JointState, "/_motors_response", 10)

self.timer = None

Expand All @@ -72,7 +70,7 @@ def start_publishing_fake_hardware(self):
self.publish_fake_hardware_messages,
)

# TODO: @delipl namespaces have not been implemented in microros yet
# TODO: @delihus namespaces have not been implemented in microros yet
def publish_fake_hardware_messages(self):
imu_msg = Imu()
imu_msg.header.stamp = self.get_clock().now().to_msg()
Expand All @@ -89,22 +87,22 @@ def publish_fake_hardware_messages(self):
joint_state_msg.position = [0.0, 0.0, 0.0, 0.0]
joint_state_msg.velocity = [0.0, 0.0, 0.0, 0.0]

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


def controller_readings_test(node, robot_name="ROSbot"):
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
msgs_received_flag = node.joint_state_msg_event.wait(10.0)
assert msgs_received_flag, (
f"{robot_name}: expected JointStates message but it was not received. Check"
" joint_state_broadcaster!"
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)
msgs_received_flag = node.odom_msg_event.wait(10.0)
assert msgs_received_flag, (
f"{robot_name}: expected Odom message but it was not received. Check"
" rosbot_base_controller!"
f"{robot_name}: Expected Odom message but it was not received. Check "
"rosbot_base_controller!"
)
msgs_received_flag = node.imu_msg_event.wait(timeout=10.0)
msgs_received_flag = node.imu_msg_event.wait(10.0)
assert (
msgs_received_flag
), f"{robot_name}: expected Imu message but it was not received. Check imu_broadcaster!"
), f"{robot_name}: Expected Imu message but it was not received. Check imu_broadcaster!"

0 comments on commit 0be0c3a

Please sign in to comment.