Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions ur_robot_driver/doc/hardware_interface_parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,11 @@ If set to false, the ROS control cycle will wait for the robot to send a status
shown that better real-time performance is achievable when setting this to ``true``. Required to be
set to ``true`` when combining with other hardware components.

primary_configuration_timeout (default: "1000")
----------------------------------------------------------

Timeout in milliseconds for waiting for primary client configuration data. This parameter controls how long the driver waits for the robot to provide its configuration data during initialization.

output_recipe_filename (Required)
---------------------------------

Expand Down
4 changes: 4 additions & 0 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -656,6 +656,9 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
const bool use_tool_communication = (info_.hardware_parameters["use_tool_communication"] == "true") ||
(info_.hardware_parameters["use_tool_communication"] == "True");

// Timeout for waiting for primary client configuration data
const int primary_configuration_timeout = std::stoi(info_.hardware_parameters["primary_configuration_timeout"]);

// Hash of the calibration reported by the robot. This is used for validating the robot
// description is using the correct calibration. If the robot's calibration doesn't match this
// hash, an error will be printed. You can use the robot as usual, however Cartesian poses of the
Expand Down Expand Up @@ -734,6 +737,7 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
driver_config.reverse_ip = reverse_ip;
driver_config.servoj_gain = static_cast<uint32_t>(servoj_gain);
driver_config.servoj_lookahead_time = servoj_lookahead_time;
driver_config.primary_configuration_timeout = std::chrono::milliseconds(static_cast<int>(primary_configuration_timeout));
driver_config.non_blocking_read = non_blocking_read_;
driver_config.tool_comm_setup = std::move(tool_comm_setup);
driver_config.handle_program_state =
Expand Down
2 changes: 2 additions & 0 deletions ur_robot_driver/urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
script_command_port:=50004
trajectory_port:=50003
non_blocking_read:=true
primary_configuration_timeout:=1000
robot_receive_timeout:=0.04
rw_rate:=0
">
Expand Down Expand Up @@ -60,6 +61,7 @@
<param name="trajectory_port">${trajectory_port}</param>
<param name="tf_prefix">${tf_prefix}</param>
<param name="non_blocking_read">${non_blocking_read}</param>
<param name="primary_configuration_timeout">${primary_configuration_timeout}</param>
<param name="servoj_gain">2000</param>
<param name="servoj_lookahead_time">0.03</param>
<param name="use_tool_communication">${use_tool_communication}</param>
Expand Down
2 changes: 2 additions & 0 deletions ur_robot_driver/urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
<xacro:arg name="reverse_port" default="50001"/>
<xacro:arg name="script_sender_port" default="50002"/>
<xacro:arg name="trajectory_port" default="50003"/>
<xacro:arg name="primary_configuration_timeout" default="1000"/>
<!-- tool communication related parameters-->
<xacro:arg name="use_tool_communication" default="false" />
<xacro:arg name="tool_voltage" default="0" />
Expand Down Expand Up @@ -93,6 +94,7 @@
tool_device_name="$(arg tool_device_name)"
tool_tcp_port="$(arg tool_tcp_port)"
robot_ip="$(arg robot_ip)"
primary_configuration_timeout="$(arg primary_configuration_timeout)"
script_filename="$(arg script_filename)"
output_recipe_filename="$(arg output_recipe_filename)"
input_recipe_filename="$(arg input_recipe_filename)"
Expand Down