Skip to content

Commit 5b0ae48

Browse files
committed
Add twist to hardware interface
1 parent f64eeb5 commit 5b0ae48

File tree

3 files changed

+63
-3
lines changed

3 files changed

+63
-3
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,7 @@ enum StoppingInterface
9797
STOP_TOOL_CONTACT,
9898
STOP_MOTION_PRIMITIVES,
9999
STOP_TORQUE,
100+
STOP_TWIST,
100101
};
101102

102103
// We define our own quaternion to use it as a buffer, since we need to pass pointers to the state
@@ -193,6 +194,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
193194
urcl::vector6d_t urcl_position_commands_old_;
194195
urcl::vector6d_t urcl_velocity_commands_;
195196
urcl::vector6d_t urcl_torque_commands_;
197+
urcl::vector6d_t urcl_twist_commands_;
196198
urcl::vector6d_t urcl_joint_positions_;
197199
urcl::vector6d_t urcl_joint_velocities_;
198200
urcl::vector6d_t urcl_joint_efforts_;
@@ -274,6 +276,8 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
274276
urcl::vector6d_t passthrough_trajectory_accelerations_;
275277
double passthrough_trajectory_time_from_start_;
276278

279+
bool twist_controller_running_;
280+
277281
// payload stuff
278282
urcl::vector3d_t payload_center_of_gravity_;
279283
double payload_mass_;
@@ -375,6 +379,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
375379
const std::string FORCE_MODE_GPIO = "force_mode";
376380
const std::string FREEDRIVE_MODE_GPIO = "freedrive_mode";
377381
const std::string TOOL_CONTACT_GPIO = "tool_contact";
382+
const std::string TWIST_GPIO = "twist";
378383

379384
std::unordered_map<std::string, std::unordered_map<std::string, bool>> mode_compatibility_;
380385
};

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 50 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@ URPositionHardwareInterface::URPositionHardwareInterface()
6969
mode_compatibility_[hardware_interface::HW_IF_POSITION][FREEDRIVE_MODE_GPIO] = false;
7070
mode_compatibility_[hardware_interface::HW_IF_POSITION][TOOL_CONTACT_GPIO] = true;
7171
mode_compatibility_[hardware_interface::HW_IF_POSITION][HW_IF_MOTION_PRIMITIVES] = false;
72+
mode_compatibility_[hardware_interface::HW_IF_POSITION][TWIST_GPIO] = false;
7273

7374
mode_compatibility_[hardware_interface::HW_IF_VELOCITY][hardware_interface::HW_IF_POSITION] = false;
7475
mode_compatibility_[hardware_interface::HW_IF_VELOCITY][hardware_interface::HW_IF_EFFORT] = false;
@@ -77,6 +78,7 @@ URPositionHardwareInterface::URPositionHardwareInterface()
7778
mode_compatibility_[hardware_interface::HW_IF_VELOCITY][FREEDRIVE_MODE_GPIO] = false;
7879
mode_compatibility_[hardware_interface::HW_IF_VELOCITY][TOOL_CONTACT_GPIO] = true;
7980
mode_compatibility_[hardware_interface::HW_IF_VELOCITY][HW_IF_MOTION_PRIMITIVES] = false;
81+
mode_compatibility_[hardware_interface::HW_IF_VELOCITY][TWIST_GPIO] = true;
8082

8183
mode_compatibility_[hardware_interface::HW_IF_EFFORT][hardware_interface::HW_IF_POSITION] = false;
8284
mode_compatibility_[hardware_interface::HW_IF_EFFORT][hardware_interface::HW_IF_VELOCITY] = false;
@@ -93,6 +95,7 @@ URPositionHardwareInterface::URPositionHardwareInterface()
9395
mode_compatibility_[FORCE_MODE_GPIO][FREEDRIVE_MODE_GPIO] = false;
9496
mode_compatibility_[FORCE_MODE_GPIO][TOOL_CONTACT_GPIO] = false;
9597
mode_compatibility_[FORCE_MODE_GPIO][HW_IF_MOTION_PRIMITIVES] = true;
98+
mode_compatibility_[FORCE_MODE_GPIO][TWIST_GPIO] = false;
9699

97100
mode_compatibility_[PASSTHROUGH_GPIO][hardware_interface::HW_IF_POSITION] = false;
98101
mode_compatibility_[PASSTHROUGH_GPIO][hardware_interface::HW_IF_VELOCITY] = false;
@@ -101,15 +104,16 @@ URPositionHardwareInterface::URPositionHardwareInterface()
101104
mode_compatibility_[PASSTHROUGH_GPIO][FREEDRIVE_MODE_GPIO] = false;
102105
mode_compatibility_[PASSTHROUGH_GPIO][TOOL_CONTACT_GPIO] = true;
103106
mode_compatibility_[PASSTHROUGH_GPIO][HW_IF_MOTION_PRIMITIVES] = false;
107+
mode_compatibility_[PASSTHROUGH_GPIO][TWIST_GPIO] = false;
104108

105109
mode_compatibility_[FREEDRIVE_MODE_GPIO][hardware_interface::HW_IF_POSITION] = false;
106110
mode_compatibility_[FREEDRIVE_MODE_GPIO][hardware_interface::HW_IF_VELOCITY] = false;
107111
mode_compatibility_[FREEDRIVE_MODE_GPIO][hardware_interface::HW_IF_EFFORT] = false;
108112
mode_compatibility_[FREEDRIVE_MODE_GPIO][FORCE_MODE_GPIO] = false;
109113
mode_compatibility_[FREEDRIVE_MODE_GPIO][PASSTHROUGH_GPIO] = false;
110114
mode_compatibility_[FREEDRIVE_MODE_GPIO][TOOL_CONTACT_GPIO] = false;
111-
mode_compatibility_[FREEDRIVE_MODE_GPIO][TOOL_CONTACT_GPIO] = false;
112115
mode_compatibility_[FREEDRIVE_MODE_GPIO][HW_IF_MOTION_PRIMITIVES] = false;
116+
mode_compatibility_[FREEDRIVE_MODE_GPIO][TWIST_GPIO] = false;
113117

114118
mode_compatibility_[TOOL_CONTACT_GPIO][hardware_interface::HW_IF_POSITION] = true;
115119
mode_compatibility_[TOOL_CONTACT_GPIO][hardware_interface::HW_IF_VELOCITY] = true;
@@ -118,6 +122,7 @@ URPositionHardwareInterface::URPositionHardwareInterface()
118122
mode_compatibility_[TOOL_CONTACT_GPIO][PASSTHROUGH_GPIO] = true;
119123
mode_compatibility_[TOOL_CONTACT_GPIO][FREEDRIVE_MODE_GPIO] = false;
120124
mode_compatibility_[TOOL_CONTACT_GPIO][HW_IF_MOTION_PRIMITIVES] = true;
125+
mode_compatibility_[TOOL_CONTACT_GPIO][TWIST_GPIO] = true;
121126

122127
mode_compatibility_[HW_IF_MOTION_PRIMITIVES][hardware_interface::HW_IF_POSITION] = false;
123128
mode_compatibility_[HW_IF_MOTION_PRIMITIVES][hardware_interface::HW_IF_VELOCITY] = false;
@@ -126,6 +131,15 @@ URPositionHardwareInterface::URPositionHardwareInterface()
126131
mode_compatibility_[HW_IF_MOTION_PRIMITIVES][PASSTHROUGH_GPIO] = false;
127132
mode_compatibility_[HW_IF_MOTION_PRIMITIVES][FREEDRIVE_MODE_GPIO] = false;
128133
mode_compatibility_[HW_IF_MOTION_PRIMITIVES][TOOL_CONTACT_GPIO] = true;
134+
mode_compatibility_[HW_IF_MOTION_PRIMITIVES][TWIST_GPIO] = false;
135+
136+
mode_compatibility_[TWIST_GPIO][hardware_interface::HW_IF_POSITION] = false;
137+
mode_compatibility_[TWIST_GPIO][hardware_interface::HW_IF_VELOCITY] = false;
138+
mode_compatibility_[TWIST_GPIO][FORCE_MODE_GPIO] = false;
139+
mode_compatibility_[TWIST_GPIO][PASSTHROUGH_GPIO] = false;
140+
mode_compatibility_[TWIST_GPIO][FREEDRIVE_MODE_GPIO] = false;
141+
mode_compatibility_[TWIST_GPIO][TOOL_CONTACT_GPIO] = true;
142+
mode_compatibility_[TWIST_GPIO][HW_IF_MOTION_PRIMITIVES] = false;
129143
}
130144

131145
URPositionHardwareInterface::~URPositionHardwareInterface()
@@ -150,12 +164,14 @@ URPositionHardwareInterface::on_init(const hardware_interface::HardwareComponent
150164
urcl_position_commands_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
151165
urcl_position_commands_old_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
152166
urcl_velocity_commands_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
167+
urcl_twist_commands_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
153168
position_controller_running_ = false;
154169
velocity_controller_running_ = false;
155170
torque_controller_running_ = false;
156171
freedrive_mode_controller_running_ = false;
157172
passthrough_trajectory_controller_running_ = false;
158173
tool_contact_controller_running_ = false;
174+
twist_controller_running_ = false;
159175
runtime_state_ = static_cast<uint32_t>(rtde::RUNTIME_STATE::STOPPED);
160176
pausing_state_ = PausingState::RUNNING;
161177
pausing_ramp_up_increment_ = 0.01;
@@ -515,6 +531,19 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
515531
&passthrough_trajectory_accelerations_[i]));
516532
}
517533

534+
command_interfaces.emplace_back(
535+
hardware_interface::CommandInterface(tf_prefix + TWIST_GPIO, "linear_velocity_x", &urcl_twist_commands_[0]));
536+
command_interfaces.emplace_back(
537+
hardware_interface::CommandInterface(tf_prefix + TWIST_GPIO, "linear_velocity_y", &urcl_twist_commands_[1]));
538+
command_interfaces.emplace_back(
539+
hardware_interface::CommandInterface(tf_prefix + TWIST_GPIO, "linear_velocity_z", &urcl_twist_commands_[2]));
540+
command_interfaces.emplace_back(
541+
hardware_interface::CommandInterface(tf_prefix + TWIST_GPIO, "angular_velocity_x", &urcl_twist_commands_[3]));
542+
command_interfaces.emplace_back(
543+
hardware_interface::CommandInterface(tf_prefix + TWIST_GPIO, "angular_velocity_y", &urcl_twist_commands_[4]));
544+
command_interfaces.emplace_back(
545+
hardware_interface::CommandInterface(tf_prefix + TWIST_GPIO, "angular_velocity_z", &urcl_twist_commands_[5]));
546+
518547
command_interfaces.emplace_back(hardware_interface::CommandInterface(
519548
tf_prefix + TOOL_CONTACT_GPIO, "tool_contact_set_state", &tool_contact_set_state_));
520549

@@ -989,10 +1018,10 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
9891018
urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP, 0,
9901019
urcl::RobotReceiveTimeout::millisec(1000 * 5.0 / static_cast<double>(info_.rw_rate)));
9911020
check_passthrough_trajectory_controller();
992-
9931021
} else if (motion_primitives_forward_controller_running_) {
9941022
handleMoprimCommands();
995-
1023+
} else if (twist_controller_running_) {
1024+
ur_driver_->writeJointCommand(urcl_twist_commands_, urcl::comm::ControlMode::MODE_SPEEDL, receive_timeout_);
9961025
} else {
9971026
ur_driver_->writeKeepalive();
9981027
}
@@ -1282,6 +1311,9 @@ hardware_interface::return_type URPositionHardwareInterface::prepare_command_mod
12821311
if (motion_primitives_forward_controller_running_) {
12831312
control_modes[i].push_back(HW_IF_MOTION_PRIMITIVES);
12841313
}
1314+
if (twist_controller_running_) {
1315+
control_modes[i].push_back(TWIST_GPIO);
1316+
}
12851317
}
12861318

12871319
auto is_mode_compatible = [this](const std::string& mode, const std::vector<std::string>& other_modes) {
@@ -1311,6 +1343,7 @@ hardware_interface::return_type URPositionHardwareInterface::prepare_command_mod
13111343
{ tf_prefix + FREEDRIVE_MODE_GPIO + "/async_success", FREEDRIVE_MODE_GPIO },
13121344
{ tf_prefix + TOOL_CONTACT_GPIO + "/tool_contact_set_state", TOOL_CONTACT_GPIO },
13131345
{ tf_prefix + HW_IF_MOTION_PRIMITIVES + "/motion_type", HW_IF_MOTION_PRIMITIVES },
1346+
{ tf_prefix + TWIST_GPIO + "/linear_velocity_x", TWIST_GPIO }
13141347
};
13151348

13161349
for (auto& item : start_modes_to_check) {
@@ -1363,6 +1396,7 @@ hardware_interface::return_type URPositionHardwareInterface::prepare_command_mod
13631396
StoppingInterface::STOP_TOOL_CONTACT },
13641397
{ tf_prefix + HW_IF_MOTION_PRIMITIVES + "/motion_type", HW_IF_MOTION_PRIMITIVES,
13651398
StoppingInterface::STOP_MOTION_PRIMITIVES },
1399+
{ tf_prefix + TWIST_GPIO + "/linear_velocity_x", TWIST_GPIO, StoppingInterface::STOP_TWIST }
13661400
};
13671401
for (auto& item : stop_modes_to_check) {
13681402
if (key == std::get<0>(item)) {
@@ -1426,6 +1460,7 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
14261460
freedrive_activated_ = false;
14271461
freedrive_mode_abort_ = 1.0;
14281462
}
1463+
14291464
if (stop_modes_.size() != 0 && std::find(stop_modes_[0].begin(), stop_modes_[0].end(),
14301465
StoppingInterface::STOP_MOTION_PRIMITIVES) != stop_modes_[0].end()) {
14311466
motion_primitives_forward_controller_running_ = false;
@@ -1440,6 +1475,12 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
14401475
ur_driver_->endToolContact();
14411476
}
14421477

1478+
if (stop_modes_.size() != 0 &&
1479+
std::find(stop_modes_[0].begin(), stop_modes_[0].end(), StoppingInterface::STOP_TWIST) != stop_modes_[0].end()) {
1480+
twist_controller_running_ = false;
1481+
urcl_twist_commands_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
1482+
}
1483+
14431484
if (start_modes_.size() != 0 && std::find(start_modes_[0].begin(), start_modes_[0].end(),
14441485
hardware_interface::HW_IF_POSITION) != start_modes_[0].end()) {
14451486
velocity_controller_running_ = false;
@@ -1507,6 +1548,12 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
15071548
std::find(start_modes_[0].begin(), start_modes_[0].end(), TOOL_CONTACT_GPIO) != start_modes_[0].end()) {
15081549
tool_contact_controller_running_ = true;
15091550
}
1551+
if (start_modes_[0].size() != 0 &&
1552+
std::find(start_modes_[0].begin(), start_modes_[0].end(), TWIST_GPIO) != start_modes_[0].end()) {
1553+
velocity_controller_running_ = false;
1554+
position_controller_running_ = false;
1555+
twist_controller_running_ = true;
1556+
}
15101557
start_modes_.clear();
15111558
stop_modes_.clear();
15121559

ur_robot_driver/urdf/ur.ros2_control.xacro

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -298,6 +298,14 @@
298298
<command_interface name="trajectory_size"/>
299299
</gpio>
300300

301+
<gpio name="${tf_prefix}twist">
302+
<command_interface name="linear_velocity_x"/>
303+
<command_interface name="linear_velocity_y"/>
304+
<command_interface name="linear_velocity_z"/>
305+
<command_interface name="angular_velocity_x"/>
306+
<command_interface name="angular_velocity_y"/>
307+
<command_interface name="angular_velocity_z"/>
308+
</gpio>
301309

302310
<gpio name="${tf_prefix}get_robot_software_version">
303311
<state_interface name="get_version_major">

0 commit comments

Comments
 (0)