UR3e wrist_3_joint infinite joint never works properly
Affected ROS2 Driver version(s)
1noble.20250624
Used ROS distribution.
Jazzy
Which combination of platform is the ROS driver running on.
Docker
How is the UR ROS2 Driver installed.
From binary packets
Which robot platform is the driver connected to.
URSim in docker
Robot SW / URSim version(s)
5.23
How is the ROS driver used.
Headless without using the teach pendant
Issue details
Summary
UR3 and UR3e according to the specifications has infinite end effector wrist but it never seems to work with ROS2 due to a combination of issues.
Issue details
It is well known that robot planners struggle at +-180 degrees wrap-around. This causes UR3e to not perform according to specifications. If the robot does execute on these bad trajectories, it causes the robot to be in a irrecoverable state (INVALID_START_STATE). Only when restarting the Robot/URSim completely can I start planning/executing trajectories again.
Planning using different planners
https://github.com/user-attachments/assets/51585c33-efb6-4d29-b965-5de4224710e7
Incrementing joints directly
https://github.com/user-attachments/assets/12b46476-8674-4c75-a242-8d1e74bf173b
Invalid start state
https://github.com/user-attachments/assets/a8a5f452-f1d3-4099-9905-a30b1887aef9
Steps to Reproduce
- Start the UR3-e URSim
- Install
ros-jazzy-urpackage - Launch the UR driver using
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur3e robot_ip:=192.168.56.101 headless_mode:=true - Launch the MoveIt driver using
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur3e launch_rviz:=true
Expected Behavior
Infinite joint should work or should be documented that it does not work with ROS2 or specific planners.
Workaround Suggestion
I am able to replicate UR3e infinite wrist in URScript but it is less than ideal.
Relevant log output
Accept Public visibility
- [x] I agree to make this context public
Hi, thank you for reaching out. Indeed we've had some discussions about this recently. MoveIt's planning capabilities are way out of the scope of this repository, actually.
That being said, our intention was to bring the infinite wrist to ROS, as it is with the real robot. However, that seems to have a couple of side effects:
- The JTC sets the start state of all continuous joints into the range of [-pi, pi] (https://github.com/ros-controls/ros2_controllers/blob/dca8f45ea8b96088bbeb9e54dc963eea087ebe50/joint_trajectory_controller/src/trajectory.cpp#L54)
- It is totally fine to define and execute a trajectory leaving the -pi, pi range which will leave the robot in a state where it cannot be operated using the JTC anymore due to the abovementioned reasons.
- MoveIt expects a continuous joint to be inside the -pi, pi range (https://github.com/moveit/moveit2/blob/4fc5c824a8af658d000d58b9f8f6eafbd4d81875/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp#L112-L122 and https://github.com/moveit/moveit2/blob/4fc5c824a8af658d000d58b9f8f6eafbd4d81875/moveit_core/robot_model/src/revolute_joint_model.cpp#L220-L235). If it is outside of that, a START_STATE_INVALID "Start state out of bounds." will be thrown.
In my opinion those things are errors in the upstream library and I would like to strive towards getting them fixed in the long run.
The easiest workaround for now is:
Create your own joint_limits.yaml file and pass that to the URDF.
That can be achieved by adding it as a launch parameter to the driver:
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur3e robot_ip:=192.168.56.101 joint_limit_params_file:=/home/robot/joint_limits.yaml
The necessary changes are in the last couple of lines:
wrist_3_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 9.0
max_velocity: !degrees 360.0
max_position: !degrees 360.0
min_position: !degrees -360.0
If you create a custom URDF for your application (which is probably a good idea, anyway), you can add your custom joint limits configuration there. See the custom workcell example for details on that. In my experience, It's usually a good idea to further restrict the joint limits for moveit planning in your custom moveit config package, as well, to reduce the "weird" motions.
Thanks for the reply. That makes the issue very clear. I have already been avoiding bad trajectories with path constraints but the wrap-around issue has been persistent issue, which requires a return to start state operation on every robot run. I have tested your workaround and it does increase the operating joint space to -2pi to 2pi, so that is very helpful.
I'm glad to hear that you got things working the way you intended.
I'll leave this open nevertheless until we have addressed this more properly.
One more side note: In the workaround I suggested using min/max positions of 360deg. From a URDF standpoint, any limit would probably be working fine, so you could also set it to 36000 to gain 100 full revelations in each direction. I am, however, not sure what planners will do with that, as a Cartesian pose will now have a lot of possible solutions.