@@ -116,19 +116,9 @@ def lookup_tcp_in_base(self, tf_prefix, timepoint):
116
116
pass
117
117
return trans
118
118
119
- def test_force_mode_controller (self , tf_prefix ):
120
- self .assertTrue (
121
- self ._controller_manager_interface .switch_controller (
122
- strictness = SwitchController .Request .BEST_EFFORT ,
123
- activate_controllers = [
124
- "force_mode_controller" ,
125
- ],
126
- deactivate_controllers = [
127
- "scaled_joint_trajectory_controller" ,
128
- "joint_trajectory_controller" ,
129
- ],
130
- ).ok
131
- )
119
+ # Implementation of force mode test to be reused
120
+ # todo: If we move to pytest this could be done using parametrization
121
+ def run_force_mode (self , tf_prefix ):
132
122
self ._force_mode_controller_interface = ForceModeInterface (self .node )
133
123
134
124
# Create task frame for force mode
@@ -237,6 +227,49 @@ def test_force_mode_controller(self, tf_prefix):
237
227
).ok
238
228
)
239
229
230
+ def test_force_mode_controller (self , tf_prefix ):
231
+ self .assertTrue (
232
+ self ._controller_manager_interface .switch_controller (
233
+ strictness = SwitchController .Request .BEST_EFFORT ,
234
+ activate_controllers = [
235
+ "force_mode_controller" ,
236
+ ],
237
+ deactivate_controllers = [
238
+ "scaled_joint_trajectory_controller" ,
239
+ "joint_trajectory_controller" ,
240
+ ],
241
+ ).ok
242
+ )
243
+ self .run_force_mode (tf_prefix )
244
+
245
+ def test_force_mode_controller_with_passthrough_controller (self , tf_prefix ):
246
+ self .assertTrue (
247
+ self ._controller_manager_interface .switch_controller (
248
+ strictness = SwitchController .Request .BEST_EFFORT ,
249
+ activate_controllers = [
250
+ "passthrough_trajectory_controller" ,
251
+ ],
252
+ deactivate_controllers = [
253
+ "scaled_joint_trajectory_controller" ,
254
+ "joint_trajectory_controller" ,
255
+ ],
256
+ ).ok
257
+ )
258
+ time .sleep (1 )
259
+ self .assertTrue (
260
+ self ._controller_manager_interface .switch_controller (
261
+ strictness = SwitchController .Request .BEST_EFFORT ,
262
+ activate_controllers = [
263
+ "force_mode_controller" ,
264
+ ],
265
+ deactivate_controllers = [
266
+ "scaled_joint_trajectory_controller" ,
267
+ "joint_trajectory_controller" ,
268
+ ],
269
+ ).ok
270
+ )
271
+ self .run_force_mode (tf_prefix )
272
+
240
273
def test_illegal_force_mode_types (self , tf_prefix ):
241
274
self .assertTrue (
242
275
self ._controller_manager_interface .switch_controller (
@@ -443,7 +476,8 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
443
476
trans_after_wait = self .lookup_tcp_in_base (tf_prefix , self .node .get_clock ().now ())
444
477
445
478
self .assertAlmostEqual (
446
- trans_before_wait .transform .translation .z , trans_after_wait .transform .translation .z
479
+ trans_before_wait .transform .translation .z ,
480
+ trans_after_wait .transform .translation .z ,
447
481
)
448
482
449
483
def test_params_out_of_range_fails (self , tf_prefix ):
0 commit comments