Skip to content

Commit 657c035

Browse files
Lennart Nachtigallfmauch
authored andcommitted
This commits adds additional configuration parameters needed for multiarm support.
Additionally is cleans up the parameters parsing in the on_activate method. Added parameters: - trajectory_port - script_command_port - keep_alive_count See Universal_Robots_ROS2_Description for more explainations Minor comment adaptions Code formatting Update prefix -> tf_prefix Update ur_bringup launchfile, as well Until we really deprecate ur_bringup, we'll have to keep it up to date. Update binary build dependencies Since with recent changes we need the latest description, we should modify the dependencies files, as well. (cherry picked from commit d2093ae)
1 parent 82f8a22 commit 657c035

File tree

4 files changed

+51
-45
lines changed

4 files changed

+51
-45
lines changed

Universal_Robots_ROS2_Driver-not-released.humble.repos

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,7 @@
44
# Once Upstream packages are released and synced to the target distributions in the required
55
# version, the entry in this file shall be removed again.
66
repositories:
7+
Universal_Robots_ROS2_Description:
8+
type: git
9+
url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Description.git
10+
version: ros2

ur_bringup/launch/ur_control.launch.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ def launch_setup(context, *args, **kwargs):
5151
controllers_file = LaunchConfiguration("controllers_file")
5252
description_package = LaunchConfiguration("description_package")
5353
description_file = LaunchConfiguration("description_file")
54-
prefix = LaunchConfiguration("prefix")
54+
tf_prefix = LaunchConfiguration("tf_prefix")
5555
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
5656
fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")
5757
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
@@ -133,8 +133,8 @@ def launch_setup(context, *args, **kwargs):
133133
"output_recipe_filename:=",
134134
output_recipe_filename,
135135
" ",
136-
"prefix:=",
137-
prefix,
136+
"tf_prefix:=",
137+
tf_prefix,
138138
" ",
139139
"use_fake_hardware:=",
140140
use_fake_hardware,
@@ -420,10 +420,10 @@ def generate_launch_description():
420420
)
421421
declared_arguments.append(
422422
DeclareLaunchArgument(
423-
"prefix",
423+
"tf_prefix",
424424
default_value='""',
425425
description="Prefix of the joint names, useful for \
426-
multi-robot setup. If changed than also joint names in the controllers' configuration \
426+
multi-robot setup. If changed, also joint names in the controllers' configuration \
427427
have to be updated.",
428428
)
429429
)

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ def launch_setup(context, *args, **kwargs):
5151
controllers_file = LaunchConfiguration("controllers_file")
5252
description_package = LaunchConfiguration("description_package")
5353
description_file = LaunchConfiguration("description_file")
54-
prefix = LaunchConfiguration("prefix")
54+
tf_prefix = LaunchConfiguration("tf_prefix")
5555
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
5656
fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")
5757
controller_spawner_timeout = LaunchConfiguration("controller_spawner_timeout")
@@ -136,8 +136,8 @@ def launch_setup(context, *args, **kwargs):
136136
"output_recipe_filename:=",
137137
output_recipe_filename,
138138
" ",
139-
"prefix:=",
140-
prefix,
139+
"tf_prefix:=",
140+
tf_prefix,
141141
" ",
142142
"use_fake_hardware:=",
143143
use_fake_hardware,
@@ -419,10 +419,10 @@ def generate_launch_description():
419419
)
420420
declared_arguments.append(
421421
DeclareLaunchArgument(
422-
"prefix",
422+
"tf_prefix",
423423
default_value='""',
424-
description="Prefix of the joint names, useful for \
425-
multi-robot setup. If changed than also joint names in the controllers' configuration \
424+
description="tf_prefix of the joint names, useful for \
425+
multi-robot setup. If changed, also joint names in the controllers' configuration \
426426
have to be updated.",
427427
)
428428
)

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 36 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -281,117 +281,118 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
281281
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Starting ...please wait...");
282282

283283
// The robot's IP address.
284-
std::string robot_ip = info_.hardware_parameters["robot_ip"];
284+
const std::string robot_ip = info_.hardware_parameters["robot_ip"];
285285
// Path to the urscript code that will be sent to the robot
286-
std::string script_filename = info_.hardware_parameters["script_filename"];
286+
const std::string script_filename = info_.hardware_parameters["script_filename"];
287287
// Path to the file containing the recipe used for requesting RTDE outputs.
288-
std::string output_recipe_filename = info_.hardware_parameters["output_recipe_filename"];
288+
const std::string output_recipe_filename = info_.hardware_parameters["output_recipe_filename"];
289289
// Path to the file containing the recipe used for requesting RTDE inputs.
290-
std::string input_recipe_filename = info_.hardware_parameters["input_recipe_filename"];
290+
const std::string input_recipe_filename = info_.hardware_parameters["input_recipe_filename"];
291291
// Start robot in headless mode. This does not require the 'External Control' URCap to be running
292292
// on the robot, but this will send the URScript to the robot directly. On e-Series robots this
293293
// requires the robot to run in 'remote-control' mode.
294-
bool headless_mode =
294+
const bool headless_mode =
295295
(info_.hardware_parameters["headless_mode"] == "true") || (info_.hardware_parameters["headless_mode"] == "True");
296296
// Port that will be opened to communicate between the driver and the robot controller.
297-
int reverse_port = stoi(info_.hardware_parameters["reverse_port"]);
297+
const int reverse_port = stoi(info_.hardware_parameters["reverse_port"]);
298298
// The driver will offer an interface to receive the program's URScript on this port.
299-
int script_sender_port = stoi(info_.hardware_parameters["script_sender_port"]);
300-
// IP that will be used for the robot controller to communicate back to the driver.
299+
const int script_sender_port = stoi(info_.hardware_parameters["script_sender_port"]);
300+
// std::string tf_prefix = info_.hardware_parameters["tf_prefix"];
301+
// std::string tf_prefix;
302+
303+
// The ip address of the host the driver runs on
301304
std::string reverse_ip = info_.hardware_parameters["reverse_ip"];
302305
if (reverse_ip == "0.0.0.0") {
303306
reverse_ip = "";
304307
}
305-
// Port that will be opened to send trajectory points from the driver to the robot. Note: this feature hasn't been
306-
// implemented in ROS2
307-
int trajectory_port = 50003;
308-
// Port that will be opened to forward script commands from the driver to the robot
309-
int script_command_port = stoi(info_.hardware_parameters["script_command_port"]);
310-
// std::string tf_prefix = info_.hardware_parameters["tf_prefix"];
311-
// std::string tf_prefix;
308+
309+
// Port (on the host pc) of the trajectory interface
310+
const int trajectory_port = stoi(info_.hardware_parameters["trajectory_port"]);
311+
312+
// Port (on the host PC) that will be used to forward script commands from the driver to the robot
313+
const int script_command_port = stoi(info_.hardware_parameters["script_command_port"]);
312314

313315
// Enables non_blocking_read mode. Should only be used with combined_robot_hw. Disables error generated when read
314316
// returns without any data, sets the read timeout to zero, and synchronises read/write operations. Enabling this when
315317
// not used with combined_robot_hw can suppress important errors and affect real-time performance.
316-
non_blocking_read_ = static_cast<bool>(stoi(info_.hardware_parameters["non_blocking_read"]));
318+
non_blocking_read_ = (info_.hardware_parameters["non_blocking_read"] == "true") ||
319+
(info_.hardware_parameters["non_blocking_read"] == "True");
317320

318321
// Specify gain for servoing to position in joint space.
319322
// A higher gain can sharpen the trajectory.
320-
int servoj_gain = stoi(info_.hardware_parameters["servoj_gain"]);
323+
const int servoj_gain = stoi(info_.hardware_parameters["servoj_gain"]);
321324
// Specify lookahead time for servoing to position in joint space.
322325
// A longer lookahead time can smooth the trajectory.
323-
double servoj_lookahead_time = stod(info_.hardware_parameters["servoj_lookahead_time"]);
326+
const double servoj_lookahead_time = stod(info_.hardware_parameters["servoj_lookahead_time"]);
324327

325-
bool use_tool_communication = (info_.hardware_parameters["use_tool_communication"] == "true") ||
326-
(info_.hardware_parameters["use_tool_communication"] == "True");
328+
const bool use_tool_communication = (info_.hardware_parameters["use_tool_communication"] == "true") ||
329+
(info_.hardware_parameters["use_tool_communication"] == "True");
327330

328331
// Hash of the calibration reported by the robot. This is used for validating the robot
329332
// description is using the correct calibration. If the robot's calibration doesn't match this
330333
// hash, an error will be printed. You can use the robot as usual, however Cartesian poses of the
331334
// endeffector might be inaccurate. See the "ur_calibration" package on help how to generate your
332335
// own hash matching your actual robot.
333-
std::string calibration_checksum = info_.hardware_parameters["kinematics/hash"];
336+
const std::string calibration_checksum = info_.hardware_parameters["kinematics/hash"];
334337

335338
std::unique_ptr<urcl::ToolCommSetup> tool_comm_setup;
336339
if (use_tool_communication) {
337340
tool_comm_setup = std::make_unique<urcl::ToolCommSetup>();
338341

339342
using ToolVoltageT = std::underlying_type<urcl::ToolVoltage>::type;
340-
ToolVoltageT tool_voltage;
343+
341344
// Tool voltage that will be set as soon as the UR-Program on the robot is started. Note: This
342345
// parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE.
343346
// Then, this parameter is required.}
344-
tool_voltage = std::stoi(info_.hardware_parameters["tool_voltage"]);
345-
347+
const ToolVoltageT tool_voltage = std::stoi(info_.hardware_parameters["tool_voltage"]);
346348
tool_comm_setup->setToolVoltage(static_cast<urcl::ToolVoltage>(tool_voltage));
347349

348350
using ParityT = std::underlying_type<urcl::Parity>::type;
349-
ParityT parity;
351+
350352
// Parity used for tool communication. Will be set as soon as the UR-Program on the robot is
351353
// started. Can be 0 (None), 1 (odd) and 2 (even).
352354
//
353355
// Note: This parameter is only evaluated, when the parameter "use_tool_communication"
354356
// is set to TRUE. Then, this parameter is required.
355-
parity = std::stoi(info_.hardware_parameters["tool_parity"]);
357+
const ParityT parity = std::stoi(info_.hardware_parameters["tool_parity"]);
356358
tool_comm_setup->setParity(static_cast<urcl::Parity>(parity));
357359

358-
int baud_rate;
359360
// Baud rate used for tool communication. Will be set as soon as the UR-Program on the robot is
360361
// started. See UR documentation for valid baud rates.
361362
//
362363
// Note: This parameter is only evaluated, when the parameter "use_tool_communication"
363364
// is set to TRUE. Then, this parameter is required.
364-
baud_rate = std::stoi(info_.hardware_parameters["tool_baud_rate"]);
365+
const int baud_rate = std::stoi(info_.hardware_parameters["tool_baud_rate"]);
365366
tool_comm_setup->setBaudRate(static_cast<uint32_t>(baud_rate));
366367

367-
int stop_bits;
368368
// Number of stop bits used for tool communication. Will be set as soon as the UR-Program on the robot is
369369
// started. Can be 1 or 2.
370370
//
371371
// Note: This parameter is only evaluated, when the parameter "use_tool_communication"
372372
// is set to TRUE. Then, this parameter is required.
373-
stop_bits = std::stoi(info_.hardware_parameters["tool_stop_bits"]);
373+
const int stop_bits = std::stoi(info_.hardware_parameters["tool_stop_bits"]);
374374
tool_comm_setup->setStopBits(static_cast<uint32_t>(stop_bits));
375375

376-
int rx_idle_chars;
377376
// Number of idle chars for the RX unit used for tool communication. Will be set as soon as the UR-Program on the
378377
// robot is started. Valid values: min=1.0, max=40.0
379378
//
380379
// Note: This parameter is only evaluated, when the parameter "use_tool_communication"
381380
// is set to TRUE. Then, this parameter is required.
382-
rx_idle_chars = std::stoi(info_.hardware_parameters["tool_rx_idle_chars"]);
381+
const int rx_idle_chars = std::stoi(info_.hardware_parameters["tool_rx_idle_chars"]);
383382
tool_comm_setup->setRxIdleChars(rx_idle_chars);
384383

385-
int tx_idle_chars;
386384
// Number of idle chars for the TX unit used for tool communication. Will be set as soon as the UR-Program on the
387385
// robot is started. Valid values: min=0.0, max=40.0
388386
//
389387
// Note: This parameter is only evaluated, when the parameter "use_tool_communication"
390388
// is set to TRUE. Then, this parameter is required.
391-
tx_idle_chars = std::stoi(info_.hardware_parameters["tool_tx_idle_chars"]);
389+
const int tx_idle_chars = std::stoi(info_.hardware_parameters["tool_tx_idle_chars"]);
392390
tool_comm_setup->setTxIdleChars(tx_idle_chars);
393391
}
394392

393+
// Amount of allowed timed out reads before the reverse interface will be dropped
394+
const int keep_alive_count = std::stoi(info_.hardware_parameters["keep_alive_count"]);
395+
395396
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Initializing driver...");
396397
registerUrclLogHandler();
397398
try {
@@ -400,6 +401,7 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
400401
std::bind(&URPositionHardwareInterface::handleRobotProgramState, this, std::placeholders::_1), headless_mode,
401402
std::move(tool_comm_setup), (uint32_t)reverse_port, (uint32_t)script_sender_port, servoj_gain,
402403
servoj_lookahead_time, non_blocking_read_, reverse_ip, trajectory_port, script_command_port);
404+
ur_driver_->setKeepaliveCount(keep_alive_count);
403405
} catch (urcl::ToolCommNotAvailable& e) {
404406
RCLCPP_FATAL_STREAM(rclcpp::get_logger("URPositionHardwareInterface"), "See parameter use_tool_communication");
405407

0 commit comments

Comments
 (0)