RTDE Package to create ROS2 topics for the RTDE Field Names selected.#1707
RTDE Package to create ROS2 topics for the RTDE Field Names selected.#1707srvald wants to merge 2 commits intoUniversalRobots:mainfrom
Conversation
Codecov Report✅ All modified and coverable lines are covered by tests. Additional details and impacted files@@ Coverage Diff @@
## main #1707 +/- ##
========================================
+ Coverage 3.59% 4.96% +1.37%
========================================
Files 13 34 +21
Lines 947 3946 +2999
Branches 152 472 +320
========================================
+ Hits 34 196 +162
- Misses 843 3748 +2905
+ Partials 70 2 -68
Flags with carried forward coverage won't be shown. Click here to find out more. ☔ View full report in Codecov by Sentry. 🚀 New features to boost your workflow:
|
urfeex
left a comment
There was a problem hiding this comment.
Thank you for that PR! I think, in general the structure is really good.
I see two major things that I would like to improve:
- I don't quite understand the necessity of the rtde_client_node. It creates a publisher and a manager and then passes the publisher to the manager. I think, all the logic requiring the publisher should not be in the manager, but in the client node. From my understanding, at this point the manager would only consist of the RTDEClient and would then be obsolete.
- We can improve a lot on runtime. In the RTDE processing pipeline we should reduce the following as much as possible:
- memory allocations
- unnecessary data copies
- expensive operations such as
std::map::find()
Another feature that I would like to see is passing the publishing frequency as a parameter (Defaulting to 500Hz) that will then be used for the RTDE setup.
Adding a test that we can publish a full recipe with all possible fields would be great.
| { | ||
| std::unique_ptr<geometry_msgs::msg::TwistStamped> Converter::vector6dToTwistStamped(const std::vector<double>& data) | ||
| { | ||
| if (data.size() != 6 && data.size() != 3) { |
There was a problem hiding this comment.
That doesn't quite match the name. If it also accepts a 3d vector it should not be called vector6dToTwistStamped
| std::unique_ptr<geometry_msgs::msg::AccelStamped> Converter::vector6dToAccelStamped(const std::vector<double>& data) | ||
| { | ||
| if (data.size() != 6 && data.size() != 3) { | ||
| throw std::invalid_argument("vectordToAccelStamped: expected 6 elements"); |
There was a problem hiding this comment.
Same as above. The name suggests that it can only handle 6d vectors. Even worse, in this function sending a vector of size 3 will produce an out-of-bounds access.
|
|
||
| auto msg = std::make_unique<geometry_msgs::msg::InertiaStamped>(); | ||
| msg->header.stamp = rclcpp::Clock().now(); | ||
| msg->header.frame_id = "tool0"; |
There was a problem hiding this comment.
The frame ID comes from the fact that currently, there is only payload_inertia in RTDE. However, the conversion function doesn't necessarily have that context.
| std::unique_ptr<geometry_msgs::msg::WrenchStamped> Converter::vector6dToWrenchStamped(const std::vector<double>& data) | ||
| { | ||
| if (data.size() != 6 && data.size() != 3) { | ||
| throw std::invalid_argument("vectordToWrenchStamped: expected 6 elements"); |
There was a problem hiding this comment.
Same as above: Name doesn't match accepting 3 elements, 3 elements cause out-of-bounds read.
| vc.name = var_name; | ||
| vc.rtde_type = rtde_type; | ||
| vc.output_type = output_type; | ||
| vc.topic = "/rtde/" + var_name; |
There was a problem hiding this comment.
Let's use local ROS URIs without a leading /
| <version>0.0.1</version> | ||
| <description>Standalone RTDE client</description> | ||
|
|
||
| <maintainer email="sergi.romero-valderas@teradyne-robotics.com">Sergi Romero</maintainer> |
There was a problem hiding this comment.
| <maintainer email="sergi.romero-valderas@teradyne-robotics.com">Sergi Romero</maintainer> | |
| <author email="sergi.romero-valderas@teradyne-robotics.com">Sergi Romero</maintainer> | |
| <maintainer email="ros@universal-robots.com">Universal Robots A/S</maintainer> |
| @@ -0,0 +1,3 @@ | |||
| # ur_rtde_client | |||
|
|
|||
| A ROS 2 package providing a real-time RTDE client for Universal Robots manipulators. It reads robot state fields (e.g. robot mode, safety status, timestamps) via UR’s RTDE protocol and publishes them as ROS 2 topics. | |||
There was a problem hiding this comment.
I think, a short usage example would be great to add here.
| install(DIRECTORY include/ | ||
| DESTINATION include |
There was a problem hiding this comment.
Since we don't provide a library in this package, there is not really a point in installing the headers.
| auto it = active_variables_.find(var_name); | ||
| if (it == active_variables_.end()) | ||
| return; |
There was a problem hiding this comment.
Finding an entry in a map is a significant time factor. If we can live without it, that would be great.
I think, avoiding the maps altogether but keeping a vector of structs, where each struct contains a
- Variable name
- Config
- Publisher
That would allow to simply iterate over the vector without the requirement for any finds.
| throw std::runtime_error("Failed to get VECTOR6D data for " + var_name); | ||
| } | ||
|
|
||
| std::vector<double> vector_data(array_data.begin(), array_data.end()); |
There was a problem hiding this comment.
I think, it would be good avoiding to copy data here. Hence, the conversion functions could receive a Vector6d already.
Summary
This PR introduces a new ROS 2 package ur_rtde_client that connects to a Universal Robots controller using RTDE and publishes ROS 2 topics for the selected RTDE field names (configured at launch time).
How to execute it
The launch file requires two arguments:
Example:
ros2 launch ur_rtde_client rtde_client.launch.xml robot_ip:=172.17.0.3 output_recipe:="["payload", "robot_mode"]"This will create the following topics:
/rtde/payload/rtde/robot_modePackage Structure
publisher.*
Loads the YAML mapping (rtde_map.yaml), creates the ROS 2 publishers at runtime, and publishes the fields extracted from the RTDE data package.
rtde_manager.*
Manages the UR RTDE client lifecycle, performs initialization, and spawns a background thread that continuously fetches RTDE data when it is available.
converter.*
Converts UR RTDE field values to the corresponding ROS 2 message types.
rtde_client_node.*
ROS 2 node entrypoint. Reads launch parameters, initializes the publisher + manager, and starts communication.
rtde_map.yaml
Defines how each RTDE variable is mapped to a ROS 2 topic and message type.