Skip to content

Commit f972f76

Browse files
committed
[force mode controller] Fix the task frame orientation (#1379)
Before, we were using a RPY notation. Chaning that to an angle-axis notation should fix things. * Update force_mode example to include a pose that is not in line with one of the main axes * Make test use an arbitraty orientation This should avoid a coincitental overlap if the transformation is wrong. (cherry picked from commit 8eb4288) # Conflicts: # ur_robot_driver/test/integration_test_force_mode.py
1 parent 68a4c72 commit f972f76

File tree

1 file changed

+4
-23
lines changed

1 file changed

+4
-23
lines changed

ur_robot_driver/test/integration_test_force_mode.py

Lines changed: 4 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -133,19 +133,9 @@ def lookup_tcp_in_base(self, tf_prefix, timepoint):
133133
pass
134134
return trans
135135

136-
def test_force_mode_controller(self, tf_prefix):
137-
self.assertTrue(
138-
self._controller_manager_interface.switch_controller(
139-
strictness=SwitchController.Request.BEST_EFFORT,
140-
activate_controllers=[
141-
"force_mode_controller",
142-
],
143-
deactivate_controllers=[
144-
"scaled_joint_trajectory_controller",
145-
"joint_trajectory_controller",
146-
],
147-
).ok
148-
)
136+
# Implementation of force mode test to be reused
137+
# todo: If we move to pytest this could be done using parametrization
138+
def run_force_mode(self, tf_prefix):
149139
self._force_mode_controller_interface = ForceModeInterface(self.node)
150140

151141
# Create task frame for force mode
@@ -154,13 +144,7 @@ def test_force_mode_controller(self, tf_prefix):
154144
task_frame_pose = Pose()
155145
task_frame_pose.position = point
156146
task_frame_pose.orientation = orientation
157-
<<<<<<< HEAD
158-
header = std_msgs.msg.Header(frame_id=tf_prefix + "base")
159-
header.stamp.sec = int(time.time()) + 1
160-
header.stamp.nanosec = 0
161-
=======
162-
header = std_msgs.msg.Header(seq=1, frame_id=tf_prefix + "tool0_controller")
163-
>>>>>>> 8eb4288 ([force mode controller] Fix the task frame orientation (#1379))
147+
header = std_msgs.msg.Header(frame_id=tf_prefix + "tool0_controller")
164148
frame_stamp = PoseStamped()
165149
frame_stamp.header = header
166150
frame_stamp.pose = task_frame_pose
@@ -262,8 +246,6 @@ def test_force_mode_controller(self, tf_prefix):
262246
).ok
263247
)
264248

265-
<<<<<<< HEAD
266-
=======
267249
def test_force_mode_controller(self, tf_prefix):
268250
self.assertTrue(
269251
self._controller_manager_interface.switch_controller(
@@ -341,7 +323,6 @@ def test_force_mode_controller_with_passthrough_controller(self, tf_prefix):
341323
)
342324
self.run_force_mode(tf_prefix)
343325

344-
>>>>>>> 8eb4288 ([force mode controller] Fix the task frame orientation (#1379))
345326
def test_illegal_force_mode_types(self, tf_prefix):
346327
self.assertTrue(
347328
self._controller_manager_interface.switch_controller(

0 commit comments

Comments
 (0)