Skip to content

Commit d465561

Browse files
authored
Fix running force_mode controller alongside passthrough trajectory controller (#1210)
This probably got mixed up when merging the two together. This allows using force_mode together with other controllers. Starting of the force_mode_controller is still only allowed for the passthrough trajectory controller using the prepareSwitch mechanism.
1 parent 2dcb86e commit d465561

File tree

2 files changed

+55
-21
lines changed

2 files changed

+55
-21
lines changed

Diff for: ur_robot_driver/src/hardware_interface.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -749,14 +749,14 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
749749
check_passthrough_trajectory_controller();
750750
} else {
751751
ur_driver_->writeKeepalive();
752+
}
752753

753-
if (!std::isnan(force_mode_task_frame_[0]) && !std::isnan(force_mode_selection_vector_[0]) &&
754-
!std::isnan(force_mode_wrench_[0]) && !std::isnan(force_mode_type_) && !std::isnan(force_mode_limits_[0]) &&
755-
!std::isnan(force_mode_damping_) && !std::isnan(force_mode_gain_scaling_) && ur_driver_ != nullptr) {
756-
start_force_mode();
757-
} else if (!std::isnan(force_mode_disable_cmd_) && ur_driver_ != nullptr && force_mode_async_success_ == 2.0) {
758-
stop_force_mode();
759-
}
754+
if (!std::isnan(force_mode_task_frame_[0]) && !std::isnan(force_mode_selection_vector_[0]) &&
755+
!std::isnan(force_mode_wrench_[0]) && !std::isnan(force_mode_type_) && !std::isnan(force_mode_limits_[0]) &&
756+
!std::isnan(force_mode_damping_) && !std::isnan(force_mode_gain_scaling_) && ur_driver_ != nullptr) {
757+
start_force_mode();
758+
} else if (!std::isnan(force_mode_disable_cmd_) && ur_driver_ != nullptr && force_mode_async_success_ == 2.0) {
759+
stop_force_mode();
760760
}
761761

762762
packet_read_ = false;

Diff for: ur_robot_driver/test/integration_test_force_mode.py

+48-14
Original file line numberDiff line numberDiff line change
@@ -116,19 +116,9 @@ def lookup_tcp_in_base(self, tf_prefix, timepoint):
116116
pass
117117
return trans
118118

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):
132122
self._force_mode_controller_interface = ForceModeInterface(self.node)
133123

134124
# Create task frame for force mode
@@ -237,6 +227,49 @@ def test_force_mode_controller(self, tf_prefix):
237227
).ok
238228
)
239229

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+
240273
def test_illegal_force_mode_types(self, tf_prefix):
241274
self.assertTrue(
242275
self._controller_manager_interface.switch_controller(
@@ -443,7 +476,8 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
443476
trans_after_wait = self.lookup_tcp_in_base(tf_prefix, self.node.get_clock().now())
444477

445478
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,
447481
)
448482

449483
def test_params_out_of_range_fails(self, tf_prefix):

0 commit comments

Comments
 (0)