Skip to content

Commit 5813de6

Browse files
author
Felix Exner
committed
Added a test that sjtc correctly aborts on violation of constraints
1 parent 2159f24 commit 5813de6

File tree

1 file changed

+72
-5
lines changed

1 file changed

+72
-5
lines changed

ur_robot_driver/test/robot_driver.py

Lines changed: 72 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@
5151
from launch_testing.actions import ReadyToTest
5252
from rclpy.action import ActionClient
5353
from rclpy.node import Node
54+
from sensor_msgs.msg import JointState
5455
from std_srvs.srv import Trigger
5556
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
5657
from ur_dashboard_msgs.msg import RobotMode
@@ -382,15 +383,81 @@ def test_trajectory_scaled(self, tf_prefix):
382383
)
383384
self.assertIn(
384385
result.error_code,
385-
(
386-
FollowJointTrajectory.Result.PATH_TOLERANCE_VIOLATED,
387-
FollowJointTrajectory.Result.GOAL_TOLERANCE_VIOLATED,
388-
FollowJointTrajectory.Result.SUCCESSFUL,
389-
),
386+
(FollowJointTrajectory.Result.SUCCESSFUL,),
390387
)
391388

392389
self.node.get_logger().info("Received result")
393390

391+
def test_trajectory_scaled_aborts_on_violation(self, tf_prefix):
392+
"""Test that the robot correctly aborts the trajectory when the constraints are violated."""
393+
# Construct test trajectory
394+
test_trajectory = [
395+
(Duration(sec=6, nanosec=0), [0.0 for j in ROBOT_JOINTS]),
396+
(
397+
Duration(sec=6, nanosec=50000000),
398+
[-1.0 for j in ROBOT_JOINTS],
399+
), # physically unfeasible
400+
(Duration(sec=8, nanosec=0), [-1.5 for j in ROBOT_JOINTS]), # physically unfeasible
401+
]
402+
403+
trajectory = JointTrajectory(
404+
joint_names=[tf_prefix + joint for joint in ROBOT_JOINTS],
405+
points=[
406+
JointTrajectoryPoint(positions=test_pos, time_from_start=test_time)
407+
for (test_time, test_pos) in test_trajectory
408+
],
409+
)
410+
411+
last_joint_state = None
412+
413+
def js_cb(msg):
414+
nonlocal last_joint_state
415+
last_joint_state = msg
416+
417+
joint_state_sub = self.node.create_subscription(JointState, "/joint_states", js_cb, 1)
418+
joint_state_sub # prevent warning about unused variable
419+
420+
goal = FollowJointTrajectory.Goal(trajectory=trajectory)
421+
422+
self.node.get_logger().info("Sending goal for robot to follow")
423+
goal_response = self.call_action(
424+
"/scaled_joint_trajectory_controller/follow_joint_trajectory", goal
425+
)
426+
427+
self.assertEqual(goal_response.accepted, True)
428+
429+
if goal_response.accepted:
430+
result = self.get_result(
431+
"/scaled_joint_trajectory_controller/follow_joint_trajectory",
432+
goal_response,
433+
TIMEOUT_EXECUTE_TRAJECTORY,
434+
)
435+
self.assertIn(
436+
result.error_code,
437+
(FollowJointTrajectory.Result.PATH_TOLERANCE_VIOLATED,),
438+
)
439+
self.node.get_logger().info("Received result")
440+
441+
# self.node.get_logger().info(f"Joint state before sleep {last_joint_state.position}")
442+
state_when_aborted = last_joint_state
443+
444+
# This section is to make sure the robot stopped moving once the trajectory was aborted
445+
time.sleep(2.0)
446+
# Ugly workaround since we want to wait for a joint state in the same thread
447+
while last_joint_state == state_when_aborted:
448+
rclpy.spin_once(self.node)
449+
state_after_sleep = last_joint_state
450+
self.node.get_logger().info(f"before: {state_when_aborted.position.tolist()}")
451+
self.node.get_logger().info(f"after: {state_after_sleep.position.tolist()}")
452+
self.assertTrue(
453+
all(
454+
[
455+
abs(a - b) < 0.2
456+
for a, b in zip(state_after_sleep.position, state_when_aborted.position)
457+
]
458+
)
459+
)
460+
394461
# TODO: uncomment when JTC starts taking into account goal_time_tolerance from goal message
395462
# see https://github.com/ros-controls/ros2_controllers/issues/249
396463
# Now do the same again, but with a goal time constraint

0 commit comments

Comments
 (0)