ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Then I discovered that if I set the joint_limited parameter from "false" to "true" in the ur5_robot.urdf.xacro file and redo the moveit_config then most of the "random valid" goals configurations in RViz can find a plan. Then, I search in the internet and found "Elbow joint self-collisions break path planning when full joint space is used on UR5 #265". [..] I wonder if the issue has been resolved [..]

Resolving is actually impossible: UR robots have +- 2pi position limits on all their joints. For the elbow, this means technically it's capable of rotation twice around its origin. However, due to the way the robot is constructed, the shoulder joint will always obstruct the wrist when the elbow passes through 0 degrees.

That's what causes the planning problems, as it's impossible to get from one "side" of the search space to another for the motion planner.

So a work-around remains, and that's in place in two ways:

  1. in kinetic-devel, instantiating the macro with the joint_limited argument to the macro will reduce the position joint limits of the all joints to +- 1 pi (see here for the shoulder_pan_joint fi). This is more restrictive than needed, but guaranteed to work.
  2. in melodic-devel-staging (which will become melodic-devel), the position joint limits for the elbow joint are always set to +- 1 pi, the other joints keep their +- 2 pi limits (see here).

So both versions of the macro implement a work-around to ros-industrial/universal_robot#265, the one in melodic-devel-staging is just a little more fine-grained.

do we still need to use the joint limited versions of urdf when using Universal Robots and MoveIt at the same time.

In essence, the answer to this question would be yes (see my earlier comments).

The difference will just be that in Kinetic, you'll need to load the joint limited version of the URDF yourself, while in Melodic (and Noetic), there is only a single URDF, and it will set reduce the limit for just the elbow joint.

Then I discovered that if I set the joint_limited parameter from "false" to "true" in the ur5_robot.urdf.xacro file and redo the moveit_config then most of the "random valid" goals configurations in RViz can find a plan. Then, I search in the internet and found "Elbow joint self-collisions break path planning when full joint space is used on UR5 #265". [..] I wonder if the issue has been resolved [..]

Resolving is actually impossible: UR robots have +- 2pi position limits on all their joints. For the elbow, this means technically it's capable of rotation twice around its origin. However, due to the way the robot is constructed, the shoulder joint will always obstruct the wrist when the elbow passes through 0 degrees.

That's what causes the planning problems, as it's impossible to get from one "side" of the search space to another for the motion planner.

So a work-around remains, and that's in place in two ways:

  1. in kinetic-devel, instantiating the macro with the joint_limited argument to the macro will reduce the position joint limits of the all joints to +- 1 pi (see here for the shoulder_pan_joint fi). This is more restrictive than needed, but guaranteed to work.
  2. in melodic-devel-staging (which will become melodic-devel), the position joint limits for the elbow joint are always set to +- 1 pi, the other joints keep their +- 2 pi limits (see here).

So both versions of the macro implement a work-around to ros-industrial/universal_robot#265, the one in melodic-devel-staging is just a little more fine-grained.

do we still need to use the joint limited versions of urdf when using Universal Robots and MoveIt at the same time.

In essence, the answer to this question would be yes (see my earlier comments).

The difference will just be that in Kinetic, you'll need to load the joint limited version of the URDF yourself, while in Melodic (and Noetic), there is only a single URDF, and it will set reduce the limit for just the elbow joint.


Edit: just to clarify: the melodic-devel-staging changes have not yet been released, so users should probably still use kinetic-devel for now.