Skip to content

Commit 02ceb92

Browse files
author
Felix Exner
committed
Use a remap for the controller topic
1 parent e70e7d1 commit 02ceb92

File tree

2 files changed

+4
-1
lines changed

2 files changed

+4
-1
lines changed

ur_robot_driver/test/driver.test

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@
99
<arg name="headless_mode" value="true"/>
1010
</include>
1111

12+
<!--If the default controller changes, this remap has to be adapted, as well-->
13+
<remap from="follow_joint_trajectory" to="/scaled_pos_traj_controller/follow_joint_trajectory" />
14+
1215
<test test-name="switch_on_test" pkg="ur_robot_driver" type="switch_on_test.py" name="switch_on_test1" time-limit="60.0"/>
1316
<test test-name="io_test" pkg="ur_robot_driver" type="io_test.py" name="io_test1" time-limit="60.0"/>
1417
<test test-name="trajectory_test" pkg="ur_robot_driver" type="trajectory_test.py" name="traj_test1" time-limit="120.0"/>

ur_robot_driver/test/trajectory_test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ def __init__(self, *args):
1919
super(TrajectoryTest, self).__init__(*args)
2020
rospy.init_node('trajectory_testing_client')
2121
self.client = actionlib.SimpleActionClient(
22-
'/scaled_pos_traj_controller/follow_joint_trajectory', FollowJointTrajectoryAction)
22+
'follow_joint_trajectory', FollowJointTrajectoryAction)
2323
timeout = rospy.Duration(30)
2424
try:
2525
self.client.wait_for_server(timeout)

0 commit comments

Comments
 (0)