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

I'll touch on just a few things for which I think I am in a position to actually give you something solid. The rest I'll leave to more knowledgeable people.

[..] Sometimes the motion planner finds a solution, sometimes it doesn't. When calling group.plan() repeatedly, it might find a solution after a number of attempts, but sometimes it really doesn't seem to be able to find a motion plan.

If you're using the default planner for MoveIt -- OMPL -- you're working with a sampling-based planner. This can sometimes put you in a situation where it finds a plan, and sometimes it doesn't, or only after a few tries. See MoveIt/Motion_Planning/Overview for more information.

  • Different versions of the universal_robots package

This is a bit vague (source vs deb? different ROS distributions? v1.0.2 vs v1.0.3?), but in general the actual motion part of the driver hasn't changed that much since it was released in Fuerte. Only recently has there been a significant change, but even that was only on the sensor side (see PR117). The initial version of the IO interface seemed to cause high CPU utilisation which the UR controller didn't like. It is possible this could influence motion performance, but that is far from certain.

  • Using KDLKinematicsPlugin vs. UR5KinematicsPlugin

OpenRave IKFast plugins are blazingly fast (order of microseconds). This specific plugin was written by hand, so I don't know the actual performance figures for it. KDL based ones tend to be slower.

  • Use of the parameter limit:=true vs. limit:=false for ur_driver (is this different when using UR5KinematicsPlugin?).
  • Use of the parameter limit:=true vs. limit:=false for moveit.

As far as I know, these eventually actually resolve to the same thing. In short: MoveIt seems to have difficulty coming up with proper trajectories for joints that have limits larger than [-pi, pi] (such as the UR5/10). The limited argument just loads a different urdf where the limits have been set to [-pi, pi] for all joints.

As to a difference in planning time and / or whether this influences / is influenced by using UR5KinematicsPlugin I'll leave for others, as I don't have that much experience with it.

  • Start position of the robot arm (e.g. one of the joint states possibly outside the allowed range in case limit:=true, or maybe just a more "difficult" pose to move from?).

I'll just say that if you start the limited version of the launchfiles, and your actual arm is outside [-pi, pi] for any joint, planning will always fail. MoveIt will immediately throw an error, as for all it knows the robot is outside its limits.

I'll touch on just a few things for which I think I am in a position to actually give you something solid. The rest I'll leave to more knowledgeable people.

[..] Sometimes the motion planner finds a solution, sometimes it doesn't. When calling group.plan() repeatedly, it might find a solution after a number of attempts, but sometimes it really doesn't seem to be able to find a motion plan.

If you're using the default planner for MoveIt -- OMPL -- you're working with a sampling-based planner. This can sometimes put you in a situation where it finds a plan, and sometimes it doesn't, or only after a few tries. See MoveIt/Motion_Planning/Overview for more information.

  • Different versions of the universal_robots package

This is a bit vague (source vs deb? different ROS distributions? v1.0.2 vs v1.0.3?), but in general the actual motion part of the driver hasn't changed that much since it was released in Fuerte. Only recently has there been a significant change, but even that was only on the sensor side (see PR117). The initial version of the IO interface seemed to cause high CPU utilisation which the UR controller didn't like. It is possible this could influence motion performance, but that is far from certain.

  • Using KDLKinematicsPlugin vs. UR5KinematicsPlugin

OpenRave IKFast plugins are blazingly fast (order of microseconds). This specific plugin was written by hand, so I don't know the actual performance figures for it. KDL based ones tend to be slower.

  • Use of the parameter limit:=true vs. limit:=false for ur_driver (is this different when using UR5KinematicsPlugin?).
  • Use of the parameter limit:=true vs. limit:=false for moveit.

As far as I know, these eventually actually resolve to the same thing. In short: MoveIt seems to have difficulty coming up with proper trajectories for joints that have limits larger than [-pi, pi] (such as the UR5/10). The limited argument just loads a different urdf where the limits have been set to [-pi, pi] for all joints.

As to a difference in planning time and / or whether this influences / is influenced by using UR5KinematicsPlugin I'll leave for others, as I don't have that much experience with it.

  • Start position of the robot arm (e.g. one of the joint states possibly outside the allowed range in case limit:=true, or maybe just a more "difficult" pose to move from?).

I'll just say that if you start the limited version of the launchfiles, and your actual arm is outside [-pi, pi] for any joint, planning will always fail. MoveIt will immediately throw an error, as for all it knows the robot is outside its limits.

limits (see also universal_robot/issues/112).