Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix running force_mode controller alongside passthrough trajectory co… #1210

Merged
merged 1 commit into from
Dec 18, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 7 additions & 7 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -749,14 +749,14 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
check_passthrough_trajectory_controller();
} else {
ur_driver_->writeKeepalive();
}

if (!std::isnan(force_mode_task_frame_[0]) && !std::isnan(force_mode_selection_vector_[0]) &&
!std::isnan(force_mode_wrench_[0]) && !std::isnan(force_mode_type_) && !std::isnan(force_mode_limits_[0]) &&
!std::isnan(force_mode_damping_) && !std::isnan(force_mode_gain_scaling_) && ur_driver_ != nullptr) {
start_force_mode();
} else if (!std::isnan(force_mode_disable_cmd_) && ur_driver_ != nullptr && force_mode_async_success_ == 2.0) {
stop_force_mode();
}
if (!std::isnan(force_mode_task_frame_[0]) && !std::isnan(force_mode_selection_vector_[0]) &&
!std::isnan(force_mode_wrench_[0]) && !std::isnan(force_mode_type_) && !std::isnan(force_mode_limits_[0]) &&
!std::isnan(force_mode_damping_) && !std::isnan(force_mode_gain_scaling_) && ur_driver_ != nullptr) {
start_force_mode();
} else if (!std::isnan(force_mode_disable_cmd_) && ur_driver_ != nullptr && force_mode_async_success_ == 2.0) {
stop_force_mode();
}

packet_read_ = false;
Expand Down
62 changes: 48 additions & 14 deletions ur_robot_driver/test/integration_test_force_mode.py
Original file line number Diff line number Diff line change
Expand Up @@ -116,19 +116,9 @@ def lookup_tcp_in_base(self, tf_prefix, timepoint):
pass
return trans

def test_force_mode_controller(self, tf_prefix):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
activate_controllers=[
"force_mode_controller",
],
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
],
).ok
)
# Implementation of force mode test to be reused
# todo: If we move to pytest this could be done using parametrization
def run_force_mode(self, tf_prefix):
self._force_mode_controller_interface = ForceModeInterface(self.node)

# Create task frame for force mode
Expand Down Expand Up @@ -237,6 +227,49 @@ def test_force_mode_controller(self, tf_prefix):
).ok
)

def test_force_mode_controller(self, tf_prefix):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
activate_controllers=[
"force_mode_controller",
],
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
],
).ok
)
self.run_force_mode(tf_prefix)

def test_force_mode_controller_with_passthrough_controller(self, tf_prefix):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
activate_controllers=[
"passthrough_trajectory_controller",
],
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
],
).ok
)
time.sleep(1)
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
activate_controllers=[
"force_mode_controller",
],
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
],
).ok
)
self.run_force_mode(tf_prefix)

def test_illegal_force_mode_types(self, tf_prefix):
self.assertTrue(
self._controller_manager_interface.switch_controller(
Expand Down Expand Up @@ -443,7 +476,8 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
trans_after_wait = self.lookup_tcp_in_base(tf_prefix, self.node.get_clock().now())

self.assertAlmostEqual(
trans_before_wait.transform.translation.z, trans_after_wait.transform.translation.z
trans_before_wait.transform.translation.z,
trans_after_wait.transform.translation.z,
)

def test_params_out_of_range_fails(self, tf_prefix):
Expand Down
Loading