Repository Summary
Checkout URI | https://github.com/UniversalRobots/Universal_Robots_ROS_passthrough_controllers.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-06-02 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
pass_through_controllers | 0.1.0 |
README
Pass-Through Controllers
A package for ROS-controllers and HW Interface mechanisms to enable forwarding of trajectories (both joint-based and Cartesian) to the robot for interpolation.
Rationale
The idea behind these controllers is to enable forwarding (pass through) incoming trajectories directly to the robot and let the OEM driver-side take care of interpolating between the waypoints. This is useful if your application demands industrial scale trajectory execution, and you prefer not to interpolate on the ROS side. Having the complete trajectory available on the driver side can be beneficial regarding smoothness of execution and avoid issues related to sending (streaming) ad hoc commands, as is classically done with current ROS-control approaches. The controllers implement simple action servers for trajectory execution (both Cartesian and joint-based). They are meant to be light-weight and their functionality is deliberately limited to starting trajectories, canceling them, and providing real-time feedback on progress.
Note that most of the work has to be done in the hardware abstraction of the robot. And, unfortunately, this is very robot specific and hard to generalize. It’s somewhat similar to the read() and write() functions of ROS-control, which need to implement robot-specific protocols. This package provides the necessary HW interfaces to implement this feature.
Controller .yaml
An example config could look like this:
# A controller to forward joint trajectories to the robot
forward_joint_trajectories:
type: "pass_through_controllers/JointTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
# A controller to forward joint trajectories to the robot
forward_cartesian_trajectories:
type: "pass_through_controllers/CartesianTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
Examples
The integration tests from this package might give a first impression on how to use this controller.
Secondly, the ur_robot_driver
uses those controllers.
Adapting your RobotHW
The pass_through_controllers expect either a JointTrajectoryInterface
or a CartesianTrajectoryInterface
, depending on the trajectory to forward.
Registering them in your RobotHW could look like this:
#include <pass_through_controllers/trajectory_interface.h>
class YourRobot : public hardware_interface::RobotHW
{
...
// Callbacks for the pass_through_controllers' events
void startJointInterpolation(const hardware_interface::JointTrajectory& trajectory);
void startCartesianInterpolation(const hardware_interface::CartesianTrajectory& trajectory);
void cancelJointInterpolation();
void cancelCartesianInterpolation();
// New HW interfaces for trajectory forwarding
hardware_interface::JointTrajectoryInterface jnt_traj_interface_;
hardware_interface::CartesianTrajectoryInterface cart_traj_interface_;
}
And in the implementation:
```c++
YourRobot::YourRobot() { … // Register callbacks for trajectory passthrough jnt_traj_interface_.registerGoalCallback( std::bind(&HardwareInterface::startJointInterpolation, this, std::placeholders::1)); jnt_traj_interface.registerCancelCallback(std::bind(&HardwareInterface::cancelInterpolation, this)); cart_traj_interface_.registerGoalCallback( std::bind(&HardwareInterface::startCartesianInterpolation, this, std::placeholders::1)); cart_traj_interface.registerCancelCallback(std::bind(&HardwareInterface::cancelInterpolation, this)); … }
void YourRobot::startJointInterpolation(const hardware_interface::JointTrajectory& trajectory) { // Robot-specific implementation here }
void YourRobot::startCartesianInterpolation(const hardware_interface::CartesianTrajectory& trajectory) {
File truncated at 100 lines see the full file
CONTRIBUTING
Repository Summary
Checkout URI | https://github.com/UniversalRobots/Universal_Robots_ROS_passthrough_controllers.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-06-02 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
pass_through_controllers | 0.1.0 |
README
Pass-Through Controllers
A package for ROS-controllers and HW Interface mechanisms to enable forwarding of trajectories (both joint-based and Cartesian) to the robot for interpolation.
Rationale
The idea behind these controllers is to enable forwarding (pass through) incoming trajectories directly to the robot and let the OEM driver-side take care of interpolating between the waypoints. This is useful if your application demands industrial scale trajectory execution, and you prefer not to interpolate on the ROS side. Having the complete trajectory available on the driver side can be beneficial regarding smoothness of execution and avoid issues related to sending (streaming) ad hoc commands, as is classically done with current ROS-control approaches. The controllers implement simple action servers for trajectory execution (both Cartesian and joint-based). They are meant to be light-weight and their functionality is deliberately limited to starting trajectories, canceling them, and providing real-time feedback on progress.
Note that most of the work has to be done in the hardware abstraction of the robot. And, unfortunately, this is very robot specific and hard to generalize. It’s somewhat similar to the read() and write() functions of ROS-control, which need to implement robot-specific protocols. This package provides the necessary HW interfaces to implement this feature.
Controller .yaml
An example config could look like this:
# A controller to forward joint trajectories to the robot
forward_joint_trajectories:
type: "pass_through_controllers/JointTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
# A controller to forward joint trajectories to the robot
forward_cartesian_trajectories:
type: "pass_through_controllers/CartesianTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
Examples
The integration tests from this package might give a first impression on how to use this controller.
Secondly, the ur_robot_driver
uses those controllers.
Adapting your RobotHW
The pass_through_controllers expect either a JointTrajectoryInterface
or a CartesianTrajectoryInterface
, depending on the trajectory to forward.
Registering them in your RobotHW could look like this:
#include <pass_through_controllers/trajectory_interface.h>
class YourRobot : public hardware_interface::RobotHW
{
...
// Callbacks for the pass_through_controllers' events
void startJointInterpolation(const hardware_interface::JointTrajectory& trajectory);
void startCartesianInterpolation(const hardware_interface::CartesianTrajectory& trajectory);
void cancelJointInterpolation();
void cancelCartesianInterpolation();
// New HW interfaces for trajectory forwarding
hardware_interface::JointTrajectoryInterface jnt_traj_interface_;
hardware_interface::CartesianTrajectoryInterface cart_traj_interface_;
}
And in the implementation:
```c++
YourRobot::YourRobot() { … // Register callbacks for trajectory passthrough jnt_traj_interface_.registerGoalCallback( std::bind(&HardwareInterface::startJointInterpolation, this, std::placeholders::1)); jnt_traj_interface.registerCancelCallback(std::bind(&HardwareInterface::cancelInterpolation, this)); cart_traj_interface_.registerGoalCallback( std::bind(&HardwareInterface::startCartesianInterpolation, this, std::placeholders::1)); cart_traj_interface.registerCancelCallback(std::bind(&HardwareInterface::cancelInterpolation, this)); … }
void YourRobot::startJointInterpolation(const hardware_interface::JointTrajectory& trajectory) { // Robot-specific implementation here }
void YourRobot::startCartesianInterpolation(const hardware_interface::CartesianTrajectory& trajectory) {
File truncated at 100 lines see the full file