Skip to content

Commit ca2ecc1

Browse files
author
Felix Exner
committed
Add a service to disable force mode again
1 parent d96b096 commit ca2ecc1

File tree

2 files changed

+21
-16
lines changed

2 files changed

+21
-16
lines changed

ur_controllers/include/ur_controllers/force_mode_controller.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
#include <controller_interface/controller_interface.hpp>
4545
#include <geometry_msgs/msg/pose_stamped.hpp>
4646
#include <rclcpp/rclcpp.hpp>
47+
#include <std_srvs/srv/trigger.hpp>
4748
#include <ur_msgs/srv/set_force_mode.hpp>
4849

4950
#include "force_mode_controller_parameters.hpp"
@@ -120,8 +121,10 @@ class ForceModeController : public controller_interface::ControllerInterface
120121
private:
121122
bool setForceMode(const ur_msgs::srv::SetForceMode::Request::SharedPtr req,
122123
ur_msgs::srv::SetForceMode::Response::SharedPtr resp);
123-
bool disableForceMode();
124+
bool disableForceMode(const std_srvs::srv::Trigger::Request::SharedPtr req,
125+
std_srvs::srv::Trigger::Response::SharedPtr resp);
124126
rclcpp::Service<ur_msgs::srv::SetForceMode>::SharedPtr set_force_mode_srv_;
127+
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr disable_force_mode_srv_;
125128

126129
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
127130
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;

ur_controllers/src/force_mode_controller.cpp

Lines changed: 17 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
*/
3535
//----------------------------------------------------------------------
3636

37+
#include <future>
3738
#include <limits>
3839
#include <rclcpp/logging.hpp>
3940
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
@@ -134,6 +135,9 @@ ur_controllers::ForceModeController::on_configure(const rclcpp_lifecycle::State&
134135
set_force_mode_srv_ = get_node()->create_service<ur_msgs::srv::SetForceMode>(
135136
"~/start_force_mode",
136137
std::bind(&ForceModeController::setForceMode, this, std::placeholders::_1, std::placeholders::_2));
138+
disable_force_mode_srv_ = get_node()->create_service<std_srvs::srv::Trigger>(
139+
"~/stop_force_mode",
140+
std::bind(&ForceModeController::disableForceMode, this, std::placeholders::_1, std::placeholders::_2));
137141
} catch (...) {
138142
return LifecycleNodeInterface::CallbackReturn::ERROR;
139143
}
@@ -154,19 +158,15 @@ controller_interface::CallbackReturn
154158
ur_controllers::ForceModeController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
155159
{
156160
// Stop force mode if this controller is deactivated.
157-
disableForceMode();
158-
try {
159-
set_force_mode_srv_.reset();
160-
} catch (...) {
161-
return LifecycleNodeInterface::CallbackReturn::ERROR;
162-
}
161+
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
163162
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
164163
}
165164

166165
controller_interface::CallbackReturn
167166
ur_controllers::ForceModeController::on_cleanup(const rclcpp_lifecycle::State& /*previous_state*/)
168167
{
169168
set_force_mode_srv_.reset();
169+
disable_force_mode_srv_.reset();
170170
return CallbackReturn::SUCCESS;
171171
}
172172

@@ -227,7 +227,9 @@ controller_interface::return_type ur_controllers::ForceModeController::update(co
227227
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
228228
async_state_ = ASYNC_WAITING;
229229
} else {
230-
// TODO(fexner): Disable
230+
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
231+
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
232+
async_state_ = ASYNC_WAITING;
231233
}
232234
change_requested_ = false;
233235
}
@@ -322,18 +324,18 @@ bool ForceModeController::setForceMode(const ur_msgs::srv::SetForceMode::Request
322324
return true;
323325
}
324326

325-
bool ForceModeController::disableForceMode()
327+
bool ForceModeController::disableForceMode(const std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
328+
std_srvs::srv::Trigger::Response::SharedPtr resp)
326329
{
327-
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
328-
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1);
329-
330+
force_mode_active_ = false;
331+
change_requested_ = true;
330332
RCLCPP_DEBUG(get_node()->get_logger(), "Waiting for force mode to be disabled.");
331-
while (command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].get_value() == ASYNC_WAITING) {
333+
while (async_state_ == ASYNC_WAITING || change_requested_) {
332334
// Asynchronous wait until the hardware interface has set the force mode
333-
std::this_thread::sleep_for(std::chrono::milliseconds(50));
335+
std::this_thread::sleep_for(std::chrono::milliseconds(10));
334336
}
335-
bool success = static_cast<bool>(command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].get_value());
336-
if (success) {
337+
resp->success = async_state_ == 1.0;
338+
if (resp->success) {
337339
RCLCPP_INFO(get_node()->get_logger(), "Force mode has been disabled successfully.");
338340
} else {
339341
RCLCPP_ERROR(get_node()->get_logger(), "Could not disable force mode.");

0 commit comments

Comments
 (0)