Skip to content

Commit baa9f7c

Browse files
URJalaurfeex
andauthored
Apply suggestions from code review
Co-authored-by: Felix Exner <[email protected]>
1 parent 86a59ca commit baa9f7c

File tree

3 files changed

+6
-4
lines changed

3 files changed

+6
-4
lines changed

ur_controllers/include/ur_controllers/tool_contact_controller.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -90,8 +90,9 @@ class ToolContactController : public controller_interface::ControllerInterface
9090

9191
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
9292
rclcpp::TimerBase::SharedPtr goal_handle_timer_; ///< Timer to frequently check on the running goal
93-
rclcpp::Duration action_monitor_period_ = rclcpp::Duration::from_seconds(0.05);
9493

94+
// non-rt function that will be called with action_monitor_period to monitor the rt action
95+
rclcpp::Duration action_monitor_period_ = rclcpp::Duration::from_seconds(0.05);
9596
void action_handler();
9697

9798
rclcpp_action::GoalResponse goal_received_callback(const rclcpp_action::GoalUUID& /*uuid*/,
@@ -100,7 +101,7 @@ class ToolContactController : public controller_interface::ControllerInterface
100101
void
101102
goal_accepted_callback(std::shared_ptr<rclcpp_action::ServerGoalHandle<ur_msgs::action::ToolContact>> goal_handle);
102103

103-
rclcpp_action::CancelResponse goal_cancelled_callback(
104+
rclcpp_action::CancelResponse goal_canceled_callback(
104105
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ur_msgs::action::ToolContact>> goal_handle);
105106

106107
std::atomic<bool> tool_contact_enable_ = false;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -944,7 +944,7 @@ void URPositionHardwareInterface::check_tool_contact_controller()
944944
}
945945

946946
} else if (cmd_state == 5.0) {
947-
bool success = static_cast<double>(ur_driver_->endToolContact());
947+
bool success = ur_driver_->endToolContact();
948948
if (success) {
949949
// TOOL_CONTACT_SUCCESS_END
950950
tool_contact_state_ = 6.0;
@@ -1332,6 +1332,7 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
13321332
StoppingInterface::STOP_TOOL_CONTACT) != stop_modes_[0].end()) {
13331333
tool_contact_controller_running_ = false;
13341334
tool_contact_result_ = 3.0;
1335+
ur_driver_->endToolContact();
13351336
}
13361337

13371338
if (start_modes_.size() != 0 && std::find(start_modes_[0].begin(), start_modes_[0].end(),

ur_robot_driver/test/integration_test_tool_contact.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ def test_start_tool_contact_controller(self):
101101
).ok
102102
)
103103

104-
def test_goal_can_be_cancelled(self):
104+
def test_goal_can_be_canceled(self):
105105
self.assertTrue(
106106
self._controller_manager_interface.switch_controller(
107107
strictness=SwitchController.Request.BEST_EFFORT,

0 commit comments

Comments
 (0)