Skip to content

Add ROS param (robot_receive_timeout) to control reverse interface timeouts #745

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 3 commits into from
Apr 17, 2025

Conversation

cambel
Copy link
Contributor

@cambel cambel commented Apr 14, 2025

Backport of ROS2 PR UniversalRobots/Universal_Robots_ROS2_Driver#1003

Useful when the connection to the robot does not support real-time control.

If it fixes the issue #507 for me

Useful when the connection to the robot does not support real-time control
@cambel cambel force-pushed the robot_receive_timeout branch from 7c22f49 to 90013f2 Compare April 14, 2025 04:52
Copy link
Member

@urfeex urfeex left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for that contribution! Could I ask you to make sure the clang-format job succeeds? Also, I've added one comment about trajectory mode.

@@ -1354,7 +1359,7 @@ void HardwareInterface::startCartesianInterpolation(const hardware_interface::Ca
{
size_t point_number = trajectory.trajectory.points.size();
ROS_DEBUG("Starting cartesian trajectory forward");
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number);
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number, robot_receive_timeout_);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as with the other.

Suggested change
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number, robot_receive_timeout_);
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number);

@@ -1292,7 +1297,7 @@ void HardwareInterface::startJointInterpolation(const hardware_interface::JointT
{
size_t point_number = trajectory.trajectory.points.size();
ROS_DEBUG("Starting joint-based trajectory forward");
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number);
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number, robot_receive_timeout_);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For trajectory control messages the default value is a lot higher actually, since we can tolerate missing communication for a longer period. Hence, I would suggest not adding it here.

Suggested change
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number, robot_receive_timeout_);
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, point_number);

@cambel
Copy link
Contributor Author

cambel commented Apr 16, 2025

@urfeex
Thank you for checking the PR!
I have made the suggested changes.

@cambel
Copy link
Contributor Author

cambel commented Apr 16, 2025

Okay!

Copy link
Member

@urfeex urfeex left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks again!

@urfeex urfeex added requires testing Requires some (hardware) testing and removed requires testing Requires some (hardware) testing labels Apr 16, 2025
@urfeex
Copy link
Member

urfeex commented Apr 17, 2025

tested and seems to work as expected.

@urfeex urfeex merged commit ea7bbdf into UniversalRobots:master Apr 17, 2025
5 checks passed
@urfeex urfeex mentioned this pull request Apr 17, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants