Skip to content

Commit 65679b2

Browse files
authored
Fix passthrough controller to not read non-existing state_interfaces (#1314)
* passthrough_trajectory: Add a test with a full quintic trajectory * Check for state interfaces being present before attempting to read from it
1 parent 7e680a7 commit 65679b2

File tree

2 files changed

+38
-3
lines changed

2 files changed

+38
-3
lines changed

ur_controllers/src/passthrough_trajectory_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -597,7 +597,7 @@ bool PassthroughTrajectoryController::check_goal_tolerance()
597597
return false;
598598
}
599599

600-
if (!active_joint_traj_.points.back().velocities.empty()) {
600+
if (!active_joint_traj_.points.back().velocities.empty() && !joint_velocity_state_interface_.empty()) {
601601
const auto joint_vel = joint_velocity_state_interface_[i].get().get_optional();
602602
if (!joint_vel.has_value()) {
603603
return false;
@@ -607,7 +607,7 @@ bool PassthroughTrajectoryController::check_goal_tolerance()
607607
return false;
608608
}
609609
}
610-
if (!active_joint_traj_.points.back().accelerations.empty()) {
610+
if (!active_joint_traj_.points.back().accelerations.empty() && !joint_acceleration_state_interface_.empty()) {
611611
const auto joint_acc = joint_acceleration_state_interface_[i].get().get_optional();
612612
if (!joint_acc.has_value()) {
613613
return false;

ur_robot_driver/test/robot_driver.py

Lines changed: 36 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -360,7 +360,7 @@ def test_passthrough_trajectory(self, tf_prefix):
360360
)
361361
waypts = [
362362
[-1.58, -1.692, -1.4311, -0.0174, 1.5882, 0.0349],
363-
[-3, -1.692, -1.4311, -0.0174, 1.5882, 0.0349],
363+
[-2.5, -1.692, -1.4311, -0.0174, 1.5882, 0.0349],
364364
[-1.58, -1.692, -1.4311, -0.0174, 1.5882, 0.0349],
365365
]
366366
time_vec = [
@@ -392,7 +392,42 @@ def test_passthrough_trajectory(self, tf_prefix):
392392
goal_handle, TIMEOUT_EXECUTE_TRAJECTORY
393393
)
394394
self.assertEqual(result.error_code, FollowJointTrajectory.Result.SUCCESSFUL)
395+
396+
# Full quintic trajectory
397+
test_trajectory = zip(time_vec, waypts)
398+
trajectory = JointTrajectory(
399+
points=[
400+
JointTrajectoryPoint(
401+
positions=pos,
402+
time_from_start=times,
403+
velocities=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
404+
accelerations=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
405+
)
406+
for (times, pos) in test_trajectory
407+
],
408+
joint_names=[tf_prefix + ROBOT_JOINTS[i] for i in range(len(ROBOT_JOINTS))],
409+
)
410+
goal_handle = self._passthrough_forward_joint_trajectory.send_goal(
411+
trajectory=trajectory,
412+
goal_time_tolerance=goal_time_tolerance,
413+
goal_tolerance=goal_tolerance,
414+
)
415+
self.assertTrue(goal_handle.accepted)
416+
if goal_handle.accepted:
417+
result = self._passthrough_forward_joint_trajectory.get_result(
418+
goal_handle, TIMEOUT_EXECUTE_TRAJECTORY
419+
)
420+
self.assertEqual(result.error_code, FollowJointTrajectory.Result.SUCCESSFUL)
421+
395422
# Test impossible goal tolerance, should fail.
423+
test_trajectory = zip(time_vec, waypts)
424+
trajectory = JointTrajectory(
425+
points=[
426+
JointTrajectoryPoint(positions=pos, time_from_start=times)
427+
for (times, pos) in test_trajectory
428+
],
429+
joint_names=[tf_prefix + ROBOT_JOINTS[i] for i in range(len(ROBOT_JOINTS))],
430+
)
396431
goal_tolerance = [
397432
JointTolerance(position=0.000000001, name=tf_prefix + ROBOT_JOINTS[i])
398433
for i in range(len(ROBOT_JOINTS))

0 commit comments

Comments
 (0)