Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix universal robot system tests random faillure #311

Merged
merged 19 commits into from
Nov 2, 2021
Merged
4 changes: 2 additions & 2 deletions webots_ros2_tests/test/test_system_universal_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,11 +75,11 @@ def tearDownClass(cls):

def setUp(self):
self.__node = rclpy.create_node('driver_tester')
self.wait_for_clock(self.__node, messages_to_receive=120)
self.wait_for_clock(self.__node, messages_to_receive=20)

def testAbbCaughtCan(self):
# The robot should catch the can in the simulation.
self.wait_for_messages(self.__node, Range, '/abb/abbirb4600/object_present_sensor', timeout=360,
self.wait_for_messages(self.__node, Range, '/abb/abbirb4600/object_present_sensor', timeout=400,
condition=lambda message: message.range < 0.07)

def tearDown(self):
Expand Down
2 changes: 1 addition & 1 deletion webots_ros2_universal_robot/launch/multirobot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def generate_launch_description():
]
)

controller_manager_timeout = ['--controller-manager-timeout', '50']
controller_manager_timeout = ['--controller-manager-timeout', '75']
controller_manager_prefix = 'python.exe' if os.name == 'nt' else ''
ur5e_trajectory_controller_spawner = Node(
package='controller_manager',
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
"""Trajectory follower client for the ABB irb4600 robot used for multi-robot demonstration."""

import rclpy
import time
from webots_ros2_universal_robot.follow_joint_trajectory_client import FollowJointTrajectoryClient


Expand All @@ -30,7 +31,7 @@
],
'points': [
{
'positions': [0.0, 0.0, 0.0, 0., 0.0495, 0.0495, 0.0495],
'positions': [0.0, 0.0, 0.0, 0.0, 0.0495, 0.0495, 0.0495],
'time_from_start': {'sec': 0, 'nanosec': 0}
},
{
Expand All @@ -50,11 +51,11 @@
'time_from_start': {'sec': 4, 'nanosec': 0}
},
{
'positions': [1.57, -0.1, 0.95, -0.71, 0.85, 0.85, 0.6],
'positions': [1.57, -0.05, 0.90, -0.71, 0.85, 0.85, 0.6],
'time_from_start': {'sec': 5, 'nanosec': 0}
},
{
'positions': [1.57, -0.1, 0.8, -0.81, 0.0495, 0.0495, 0.0495],
'positions': [1.57, -0.05, 0.75, -0.81, 0.0495, 0.0495, 0.0495],
'time_from_start': {'sec': 6, 'nanosec': 0}
},
{
Expand All @@ -72,6 +73,11 @@
def main(args=None):
rclpy.init(args=args)
controller = FollowJointTrajectoryClient('abb_controller', '/abb/abb_joint_trajectory_controller/follow_joint_trajectory')

# Need to be sur that trajectory_controller is ready (only for slow machines).
# https://github.com/ros2/rclpy/issues/842
time.sleep(5)

controller.send_goal(GOAL, 10)
rclpy.spin(controller)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
"""Trajectory follower client for the UR5 robot used for multi-robot demonstration."""

import rclpy
import time
from webots_ros2_universal_robot.follow_joint_trajectory_client import FollowJointTrajectoryClient


Expand All @@ -30,7 +31,7 @@
],
'points': [
{
'positions': [0.0, 0.0, 0.0, 0., 0.0495, 0.0495, 0.0495],
'positions': [0.0, 0.0, 0.0, 0.0, 0.0495, 0.0495, 0.0495],
'time_from_start': {'sec': 0, 'nanosec': 0}
},
{
Expand Down Expand Up @@ -68,6 +69,11 @@
def main(args=None):
rclpy.init(args=args)
controller = FollowJointTrajectoryClient('ur5e_controller', '/ur5e/ur_joint_trajectory_controller/follow_joint_trajectory')

# Need to be sur that trajectory_controller is ready (only for slow machines).
# https://github.com/ros2/rclpy/issues/842
time.sleep(5)

controller.send_goal(GOAL, 10)
rclpy.spin(controller)

Expand Down