Skip to content

Commit 22e4804

Browse files
committed
Added service to set force mode
1 parent 43c7515 commit 22e4804

File tree

5 files changed

+189
-0
lines changed

5 files changed

+189
-0
lines changed

ur_controllers/include/ur_controllers/gpio_controller.hpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@
5353
#include "ur_msgs/srv/set_io.hpp"
5454
#include "ur_msgs/srv/set_speed_slider_fraction.hpp"
5555
#include "ur_msgs/srv/set_payload.hpp"
56+
#include "ur_msgs/srv/set_force_mode.hpp"
5657
#include "rclcpp/time.hpp"
5758
#include "rclcpp/duration.hpp"
5859
#include "std_msgs/msg/bool.hpp"
@@ -73,6 +74,32 @@ enum CommandInterfaces
7374
PAYLOAD_COG_Y = 27,
7475
PAYLOAD_COG_Z = 28,
7576
PAYLOAD_ASYNC_SUCCESS = 29,
77+
FORCE_MODE_TASK_FRAME_X = 30,
78+
FORCE_MODE_TASK_FRAME_Y = 31,
79+
FORCE_MODE_TASK_FRAME_Z = 32,
80+
FORCE_MODE_TASK_FRAME_RX = 33,
81+
FORCE_MODE_TASK_FRAME_RY = 34,
82+
FORCE_MODE_TASK_FRAME_RZ = 35,
83+
FORCE_MODE_SELECTION_VECTOR_X = 36,
84+
FORCE_MODE_SELECTION_VECTOR_Y = 37,
85+
FORCE_MODE_SELECTION_VECTOR_Z = 38,
86+
FORCE_MODE_SELECTION_VECTOR_RX = 39,
87+
FORCE_MODE_SELECTION_VECTOR_RY = 40,
88+
FORCE_MODE_SELECTION_VECTOR_RZ = 41,
89+
FORCE_MODE_WRENCH_X = 42,
90+
FORCE_MODE_WRENCH_Y = 43,
91+
FORCE_MODE_WRENCH_Z = 44,
92+
FORCE_MODE_WRENCH_RX = 45,
93+
FORCE_MODE_WRENCH_RY = 46,
94+
FORCE_MODE_WRENCH_RZ = 47,
95+
FORCE_MODE_TYPE = 48,
96+
FORCE_MODE_LIMITS_X = 49,
97+
FORCE_MODE_LIMITS_Y = 50,
98+
FORCE_MODE_LIMITS_Z = 51,
99+
FORCE_MODE_LIMITS_RX = 52,
100+
FORCE_MODE_LIMITS_RY = 53,
101+
FORCE_MODE_LIMITS_RZ = 54,
102+
FORCE_MODE_ASYNC_SUCCESS = 55,
76103
};
77104

78105
enum StateInterfaces
@@ -125,6 +152,9 @@ class GPIOController : public controller_interface::ControllerInterface
125152
bool setPayload(const ur_msgs::srv::SetPayload::Request::SharedPtr req,
126153
ur_msgs::srv::SetPayload::Response::SharedPtr resp);
127154

155+
bool setForceMode(const ur_msgs::srv::SetForceMode::Request::SharedPtr req,
156+
ur_msgs::srv::SetForceMode::Response::SharedPtr resp);
157+
128158
void publishIO();
129159

130160
void publishToolData();
@@ -150,6 +180,7 @@ class GPIOController : public controller_interface::ControllerInterface
150180
rclcpp::Service<ur_msgs::srv::SetSpeedSliderFraction>::SharedPtr set_speed_slider_srv_;
151181
rclcpp::Service<ur_msgs::srv::SetIO>::SharedPtr set_io_srv_;
152182
rclcpp::Service<ur_msgs::srv::SetPayload>::SharedPtr set_payload_srv_;
183+
rclcpp::Service<ur_msgs::srv::SetForceMode>::SharedPtr set_force_mode_srv_;
153184

154185
std::shared_ptr<rclcpp::Publisher<ur_msgs::msg::IOStates>> io_pub_;
155186
std::shared_ptr<rclcpp::Publisher<ur_msgs::msg::ToolDataMsg>> tool_data_pub_;

ur_controllers/src/gpio_controller.cpp

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,34 @@ controller_interface::InterfaceConfiguration GPIOController::command_interface_c
7878
config.names.emplace_back("payload/cog.z");
7979
config.names.emplace_back("payload/payload_async_success");
8080

81+
// force mode
82+
config.names.emplace_back("force_mode/task_frame_x");
83+
config.names.emplace_back("force_mode/task_frame_y");
84+
config.names.emplace_back("force_mode/task_frame_z");
85+
config.names.emplace_back("force_mode/task_frame_rx");
86+
config.names.emplace_back("force_mode/task_frame_ry");
87+
config.names.emplace_back("force_mode/task_frame_rz");
88+
config.names.emplace_back("force_mode/selection_vector_x");
89+
config.names.emplace_back("force_mode/selection_vector_y");
90+
config.names.emplace_back("force_mode/selection_vector_z");
91+
config.names.emplace_back("force_mode/selection_vector_rx");
92+
config.names.emplace_back("force_mode/selection_vector_ry");
93+
config.names.emplace_back("force_mode/selection_vector_rz");
94+
config.names.emplace_back("force_mode/wrench_x");
95+
config.names.emplace_back("force_mode/wrench_y");
96+
config.names.emplace_back("force_mode/wrench_z");
97+
config.names.emplace_back("force_mode/wrench_rx");
98+
config.names.emplace_back("force_mode/wrench_ry");
99+
config.names.emplace_back("force_mode/wrench_rz");
100+
config.names.emplace_back("force_mode/type");
101+
config.names.emplace_back("force_mode/limits_x");
102+
config.names.emplace_back("force_mode/limits_y");
103+
config.names.emplace_back("force_mode/limits_z");
104+
config.names.emplace_back("force_mode/limits_rx");
105+
config.names.emplace_back("force_mode/limits_ry");
106+
config.names.emplace_back("force_mode/limits_rz");
107+
config.names.emplace_back("force_mode/force_mode_async_success");
108+
81109
return config;
82110
}
83111

@@ -274,6 +302,10 @@ ur_controllers::GPIOController::on_activate(const rclcpp_lifecycle::State& /*pre
274302

275303
set_payload_srv_ = get_node()->create_service<ur_msgs::srv::SetPayload>(
276304
"~/set_payload", std::bind(&GPIOController::setPayload, this, std::placeholders::_1, std::placeholders::_2));
305+
306+
set_force_mode_srv_ = get_node()->create_service<ur_msgs::srv::SetForceMode>(
307+
"~/set_force_mode",
308+
std::bind(&GPIOController::setForceMode, this, std::placeholders::_1, std::placeholders::_2));
277309
} catch (...) {
278310
return LifecycleNodeInterface::CallbackReturn::ERROR;
279311
}
@@ -413,6 +445,44 @@ bool GPIOController::setPayload(const ur_msgs::srv::SetPayload::Request::SharedP
413445
return true;
414446
}
415447

448+
bool GPIOController::setForceMode(const ur_msgs::srv::SetForceMode::Request::SharedPtr req,
449+
ur_msgs::srv::SetForceMode::Response::SharedPtr resp)
450+
{
451+
if (req->task_frame.size() != 6 || req->selection_vector.size() != 6 || req->wrench.size() != 6 ||
452+
req->limits.size() != 6) {
453+
RCLCPP_WARN(get_node()->get_logger(), "Size of received force mode message is wrong");
454+
resp->success = false;
455+
return false;
456+
}
457+
458+
// reset success flag
459+
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
460+
461+
for (size_t i = 0; i < 6; i++) {
462+
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X + i].set_value(req->task_frame[i]);
463+
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X + i].set_value(req->selection_vector[i]);
464+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X + i].set_value(req->wrench[i]);
465+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X + i].set_value(req->limits[i]);
466+
}
467+
command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(unsigned(req->type));
468+
469+
while (command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].get_value() == ASYNC_WAITING) {
470+
// Asynchronous wait until the hardware interface has set the force mode
471+
std::this_thread::sleep_for(std::chrono::milliseconds(50));
472+
}
473+
474+
resp->success = static_cast<bool>(command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].get_value());
475+
476+
if (resp->success) {
477+
RCLCPP_INFO(get_node()->get_logger(), "Force mode has been set successfully");
478+
} else {
479+
RCLCPP_ERROR(get_node()->get_logger(), "Could not set the force mode");
480+
return false;
481+
}
482+
483+
return true;
484+
}
485+
416486
void GPIOController::initMsgs()
417487
{
418488
io_msg_.digital_in_states.resize(standard_digital_output_cmd_.size());

ur_robot_driver/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@ find_package(std_srvs REQUIRED)
3232
find_package(tf2_geometry_msgs REQUIRED)
3333
find_package(ur_client_library REQUIRED)
3434
find_package(ur_dashboard_msgs REQUIRED)
35+
find_package(ur_msgs REQUIRED)
3536

3637
include_directories(include)
3738

@@ -48,6 +49,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
4849
tf2_geometry_msgs
4950
ur_client_library
5051
ur_dashboard_msgs
52+
ur_msgs
5153
)
5254

5355
add_library(ur_robot_driver_plugin

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -189,6 +189,14 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
189189
double payload_mass_;
190190
double payload_async_success_;
191191

192+
// force mode parameters
193+
urcl::vector6d_t force_mode_task_frame_;
194+
urcl::vector6d_t force_mode_selection_vector_;
195+
urcl::vector6d_t force_mode_wrench_;
196+
urcl::vector6d_t force_mode_limits_;
197+
double force_mode_type_;
198+
double force_mode_async_success_;
199+
192200
// copy of non double values
193201
std::array<double, 18> actual_dig_out_bits_copy_;
194202
std::array<double, 18> actual_dig_in_bits_copy_;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -254,6 +254,58 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
254254
command_interfaces.emplace_back(
255255
hardware_interface::CommandInterface("payload", "payload_async_success", &payload_async_success_));
256256

257+
command_interfaces.emplace_back(
258+
hardware_interface::CommandInterface("force_mode", "task_frame_x", &force_mode_task_frame_[0]));
259+
command_interfaces.emplace_back(
260+
hardware_interface::CommandInterface("force_mode", "task_frame_y", &force_mode_task_frame_[1]));
261+
command_interfaces.emplace_back(
262+
hardware_interface::CommandInterface("force_mode", "task_frame_z", &force_mode_task_frame_[2]));
263+
command_interfaces.emplace_back(
264+
hardware_interface::CommandInterface("force_mode", "task_frame_rx", &force_mode_task_frame_[3]));
265+
command_interfaces.emplace_back(
266+
hardware_interface::CommandInterface("force_mode", "task_frame_ry", &force_mode_task_frame_[4]));
267+
command_interfaces.emplace_back(
268+
hardware_interface::CommandInterface("force_mode", "task_frame_rz", &force_mode_task_frame_[5]));
269+
command_interfaces.emplace_back(
270+
hardware_interface::CommandInterface("force_mode", "selection_vector_x", &force_mode_selection_vector_[0]));
271+
command_interfaces.emplace_back(
272+
hardware_interface::CommandInterface("force_mode", "selection_vector_y", &force_mode_selection_vector_[1]));
273+
command_interfaces.emplace_back(
274+
hardware_interface::CommandInterface("force_mode", "selection_vector_z", &force_mode_selection_vector_[2]));
275+
command_interfaces.emplace_back(
276+
hardware_interface::CommandInterface("force_mode", "selection_vector_rx", &force_mode_selection_vector_[3]));
277+
command_interfaces.emplace_back(
278+
hardware_interface::CommandInterface("force_mode", "selection_vector_ry", &force_mode_selection_vector_[4]));
279+
command_interfaces.emplace_back(
280+
hardware_interface::CommandInterface("force_mode", "selection_vector_rz", &force_mode_selection_vector_[5]));
281+
command_interfaces.emplace_back(
282+
hardware_interface::CommandInterface("force_mode", "wrench_x", &force_mode_wrench_[0]));
283+
command_interfaces.emplace_back(
284+
hardware_interface::CommandInterface("force_mode", "wrench_y", &force_mode_wrench_[1]));
285+
command_interfaces.emplace_back(
286+
hardware_interface::CommandInterface("force_mode", "wrench_z", &force_mode_wrench_[2]));
287+
command_interfaces.emplace_back(
288+
hardware_interface::CommandInterface("force_mode", "wrench_rx", &force_mode_wrench_[3]));
289+
command_interfaces.emplace_back(
290+
hardware_interface::CommandInterface("force_mode", "wrench_ry", &force_mode_wrench_[4]));
291+
command_interfaces.emplace_back(
292+
hardware_interface::CommandInterface("force_mode", "wrench_rz", &force_mode_wrench_[5]));
293+
command_interfaces.emplace_back(hardware_interface::CommandInterface("force_mode", "type", &force_mode_type_));
294+
command_interfaces.emplace_back(
295+
hardware_interface::CommandInterface("force_mode", "limits_x", &force_mode_limits_[0]));
296+
command_interfaces.emplace_back(
297+
hardware_interface::CommandInterface("force_mode", "limits_y", &force_mode_limits_[1]));
298+
command_interfaces.emplace_back(
299+
hardware_interface::CommandInterface("force_mode", "limits_z", &force_mode_limits_[2]));
300+
command_interfaces.emplace_back(
301+
hardware_interface::CommandInterface("force_mode", "limits_rx", &force_mode_limits_[3]));
302+
command_interfaces.emplace_back(
303+
hardware_interface::CommandInterface("force_mode", "limits_ry", &force_mode_limits_[4]));
304+
command_interfaces.emplace_back(
305+
hardware_interface::CommandInterface("force_mode", "limits_rz", &force_mode_limits_[5]));
306+
command_interfaces.emplace_back(
307+
hardware_interface::CommandInterface("force_mode", "force_mode_async_success", &force_mode_async_success_));
308+
257309
for (size_t i = 0; i < 18; ++i) {
258310
command_interfaces.emplace_back(hardware_interface::CommandInterface(
259311
"gpio", "standard_digital_output_cmd_" + std::to_string(i), &standard_dig_out_bits_cmd_[i]));
@@ -596,6 +648,14 @@ void URPositionHardwareInterface::initAsyncIO()
596648

597649
payload_mass_ = NO_NEW_CMD_;
598650
payload_center_of_gravity_ = { NO_NEW_CMD_, NO_NEW_CMD_, NO_NEW_CMD_ };
651+
652+
for (size_t i = 0; i < 6; i++) {
653+
force_mode_task_frame_[i] = NO_NEW_CMD_;
654+
force_mode_selection_vector_[i] = static_cast<uint32_t>(NO_NEW_CMD_);
655+
force_mode_wrench_[i] = NO_NEW_CMD_;
656+
force_mode_limits_[i] = NO_NEW_CMD_;
657+
}
658+
force_mode_type_ = static_cast<unsigned int>(NO_NEW_CMD_);
599659
}
600660

601661
void URPositionHardwareInterface::checkAsyncIO()
@@ -656,6 +716,24 @@ void URPositionHardwareInterface::checkAsyncIO()
656716
payload_mass_ = NO_NEW_CMD_;
657717
payload_center_of_gravity_ = { NO_NEW_CMD_, NO_NEW_CMD_, NO_NEW_CMD_ };
658718
}
719+
720+
if (!std::isnan(force_mode_task_frame_[0]) && !std::isnan(force_mode_selection_vector_[0]) &&
721+
!std::isnan(force_mode_wrench_[0]) && !std::isnan(force_mode_type_) && !std::isnan(force_mode_limits_[0]) &&
722+
ur_driver_ != nullptr) {
723+
urcl::vector6uint32_t force_mode_selection_vector;
724+
for (size_t i = 0; i < 6; i++) {
725+
force_mode_selection_vector[i] = force_mode_selection_vector_[i];
726+
}
727+
force_mode_async_success_ = ur_driver_->startForceMode(force_mode_task_frame_, force_mode_selection_vector,
728+
force_mode_wrench_, force_mode_type_, force_mode_limits_);
729+
for (size_t i = 0; i < 6; i++) {
730+
force_mode_task_frame_[i] = NO_NEW_CMD_;
731+
force_mode_selection_vector_[i] = static_cast<uint32_t>(NO_NEW_CMD_);
732+
force_mode_wrench_[i] = NO_NEW_CMD_;
733+
force_mode_limits_[i] = NO_NEW_CMD_;
734+
}
735+
force_mode_type_ = static_cast<unsigned int>(NO_NEW_CMD_);
736+
}
659737
}
660738

661739
void URPositionHardwareInterface::updateNonDoubleValues()

0 commit comments

Comments
 (0)