Skip to content

Commit 3c8223c

Browse files
committed
Make test use an arbitraty orientation
This should avoid a coincitental overlap if the transformation is wrong.
1 parent d90a3b2 commit 3c8223c

File tree

1 file changed

+75
-13
lines changed

1 file changed

+75
-13
lines changed

ur_robot_driver/test/integration_test_force_mode.py

Lines changed: 75 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,9 @@
4242
from tf2_ros.buffer import Buffer
4343
from tf2_ros.transform_listener import TransformListener
4444

45+
from builtin_interfaces.msg import Duration
46+
from control_msgs.action import FollowJointTrajectory
47+
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
4548
import std_msgs
4649
from controller_manager_msgs.srv import SwitchController
4750
from geometry_msgs.msg import (
@@ -52,16 +55,19 @@
5255
Twist,
5356
Wrench,
5457
Vector3,
58+
Vector3Stamped,
5559
)
5660

5761
sys.path.append(os.path.dirname(__file__))
5862
from test_common import ( # noqa: E402
63+
ActionInterface,
5964
ControllerManagerInterface,
6065
DashboardInterface,
6166
ForceModeInterface,
6267
IoStatusInterface,
6368
ConfigurationInterface,
6469
generate_driver_test_description,
70+
ROBOT_JOINTS,
6571
)
6672

6773
TIMEOUT_EXECUTE_TRAJECTORY = 30
@@ -101,6 +107,11 @@ def init_robot(self):
101107
self._controller_manager_interface = ControllerManagerInterface(self.node)
102108
self._io_status_controller_interface = IoStatusInterface(self.node)
103109
self._configuration_controller_interface = ConfigurationInterface(self.node)
110+
self._passthrough_forward_joint_trajectory = ActionInterface(
111+
self.node,
112+
"/passthrough_trajectory_controller/follow_joint_trajectory",
113+
FollowJointTrajectory,
114+
)
104115

105116
def setUp(self):
106117
self._dashboard_interface.start_robot()
@@ -127,14 +138,12 @@ def run_force_mode(self, tf_prefix):
127138
self._force_mode_controller_interface = ForceModeInterface(self.node)
128139

129140
# Create task frame for force mode
130-
point = Point(x=0.8, y=0.8, z=0.8)
141+
point = Point(x=0.0, y=0.0, z=0.0)
131142
orientation = Quaternion(x=0.7071, y=0.0, z=0.0, w=0.7071)
132143
task_frame_pose = Pose()
133144
task_frame_pose.position = point
134145
task_frame_pose.orientation = orientation
135-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "base")
136-
header.stamp.sec = int(time.time()) + 1
137-
header.stamp.nanosec = 0
146+
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "tool0_controller")
138147
frame_stamp = PoseStamped()
139148
frame_stamp.header = header
140149
frame_stamp.pose = task_frame_pose
@@ -144,7 +153,7 @@ def run_force_mode(self, tf_prefix):
144153

145154
# Create Wrench message for force mode
146155
wrench = Wrench()
147-
wrench.force = Vector3(x=0.0, y=0.0, z=5.0)
156+
wrench.force = Vector3(x=0.0, y=0.0, z=10.0)
148157
wrench.torque = Vector3(x=0.0, y=0.0, z=0.0)
149158

150159
# Specify interpretation of task frame (no transform)
@@ -183,27 +192,46 @@ def run_force_mode(self, tf_prefix):
183192
time.sleep(5.0)
184193

185194
trans_after = self.lookup_tcp_in_base(tf_prefix, self.node.get_clock().now())
195+
diff = Vector3Stamped(
196+
vector=Vector3(
197+
x=(trans_after.transform.translation.x - trans_before.transform.translation.x),
198+
y=(trans_after.transform.translation.y - trans_before.transform.translation.y),
199+
z=(trans_after.transform.translation.z - trans_before.transform.translation.z),
200+
),
201+
header=trans_after.header,
202+
)
203+
diff_in_tool0_controller = self.tf_buffer.transform(
204+
diff,
205+
tf_prefix + "tool0_controller",
206+
timeout=rclpy.time.Duration(seconds=1.0),
207+
)
186208

187209
# task frame and wrench determines the expected motion
188210
# In the example we used
189-
# - a task frame rotated pi/2 deg around the base frame's x axis
211+
# - a task frame rotated pi/2 deg around the tcp frame's x axis
190212
# - a wrench with a positive z component for the force
191-
# => we should expect a motion in negative y of the base frame
192-
self.assertTrue(trans_after.transform.translation.y < trans_before.transform.translation.y)
213+
# => we should expect a motion in negative y of the tcp frame, since we didn't to any
214+
# rotation
215+
self.assertTrue(
216+
diff_in_tool0_controller.vector.y < -0.03,
217+
)
193218
self.assertAlmostEqual(
194-
trans_after.transform.translation.x,
195-
trans_before.transform.translation.x,
219+
diff_in_tool0_controller.vector.x,
220+
0.0,
196221
delta=0.001,
222+
msg="X translation should not change",
197223
)
198224
self.assertAlmostEqual(
199-
trans_after.transform.translation.z,
200-
trans_before.transform.translation.z,
225+
diff_in_tool0_controller.vector.z,
226+
0.0,
201227
delta=0.001,
228+
msg="Z translation should not change",
202229
)
203230
self.assertTrue(
204231
are_quaternions_same(
205232
trans_after.transform.rotation, trans_before.transform.rotation, 0.001
206-
)
233+
),
234+
msg="Rotation should not change",
207235
)
208236

209237
res = self._force_mode_controller_interface.stop_force_mode()
@@ -218,6 +246,39 @@ def run_force_mode(self, tf_prefix):
218246
)
219247

220248
def test_force_mode_controller(self, tf_prefix):
249+
self.assertTrue(
250+
self._controller_manager_interface.switch_controller(
251+
strictness=SwitchController.Request.BEST_EFFORT,
252+
activate_controllers=[
253+
"passthrough_trajectory_controller",
254+
],
255+
deactivate_controllers=[
256+
"scaled_joint_trajectory_controller",
257+
"joint_trajectory_controller",
258+
"force_mode_controller",
259+
],
260+
).ok
261+
)
262+
waypts = [[-1.6, -1.55, -1.7, -1.0, 2.05, 0.5]]
263+
time_vec = [Duration(sec=5, nanosec=0)]
264+
test_trajectory = zip(time_vec, waypts)
265+
trajectory = JointTrajectory(
266+
points=[
267+
JointTrajectoryPoint(positions=pos, time_from_start=times)
268+
for (times, pos) in test_trajectory
269+
],
270+
joint_names=[tf_prefix + ROBOT_JOINTS[i] for i in range(len(ROBOT_JOINTS))],
271+
)
272+
goal_handle = self._passthrough_forward_joint_trajectory.send_goal(
273+
trajectory=trajectory,
274+
)
275+
self.assertTrue(goal_handle.accepted)
276+
if goal_handle.accepted:
277+
result = self._passthrough_forward_joint_trajectory.get_result(
278+
goal_handle, TIMEOUT_EXECUTE_TRAJECTORY
279+
)
280+
self.assertEqual(result.error_code, FollowJointTrajectory.Result.SUCCESSFUL)
281+
221282
self.assertTrue(
222283
self._controller_manager_interface.switch_controller(
223284
strictness=SwitchController.Request.BEST_EFFORT,
@@ -227,6 +288,7 @@ def test_force_mode_controller(self, tf_prefix):
227288
deactivate_controllers=[
228289
"scaled_joint_trajectory_controller",
229290
"joint_trajectory_controller",
291+
"passthrough_trajectory_controller",
230292
],
231293
).ok
232294
)

0 commit comments

Comments
 (0)