Skip to content

Commit 5109f41

Browse files
author
Felix Exner
committed
Added a test that sjtc correctly aborts on violation of constraints
1 parent ec7f5e7 commit 5109f41

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
@@ -381,15 +382,81 @@ def test_trajectory_scaled(self, tf_prefix):
381382
)
382383
self.assertIn(
383384
result.error_code,
384-
(
385-
FollowJointTrajectory.Result.PATH_TOLERANCE_VIOLATED,
386-
FollowJointTrajectory.Result.GOAL_TOLERANCE_VIOLATED,
387-
FollowJointTrajectory.Result.SUCCESSFUL,
388-
),
385+
(FollowJointTrajectory.Result.SUCCESSFUL,),
389386
)
390387

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

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

0 commit comments

Comments
 (0)