maximum velocity in MoveIt! on an UR5 robot

2,468 views
Skip to first unread message

Michael Wojtynek

unread,
Apr 3, 2015, 7:56:51 AM4/3/15
to swri-ros...@googlegroups.com

Hello everybody!

I want to increase the maximum velocity in moveit to speed up the robot movement. I’m working on an ur5 robot with ROS industrial driver and ROS indigo.
The right place to raise the velocity is the joint_limits.yaml in the config folder of the moveit config, in my opinion.

By default the yaml file looks like that excerpt:
“joint_limits:
elbow_joint:
has_velocity_limits: true
max_velocity: 3.15
has_acceleration_limits: false
max_acceleration: 0”

The joints_limit.yaml overwrites the velocity values in the URDF file. 3.15rad/s for one joint is very fast, I think. Compared to the max_velocity value the robot moves very slow. Do I have to increase also max_acceleration? What are proper values for accel? Is the range from 0.0 to 1.0 for accel? Does it make sense to increase the max_velocity higher than 3.15 rad/s?
On ROS hydro I used a quite similar setup, but there I had to decrease max_velocity values for developing. Acceleration was set to false. On hydro different max velocities worked.

There is also a max_velocity value in the ROS driver. But according to the commentary in the driver.py it has no effect on the velocity of execution. It has to be only higher than the maximum velocity value of moveit.

Another question is, why the velocity values changed in ROS-I driver (particularly in the URDF)? The wrist values increased from 3.14 to 3.2rad/s. The base, shoulder and lift joint are now rounded up to 3.15. [1]

Greetings,
Michael


[1] https://github.com/ros-industrial/universal_robot/commit/b27d7f19746e66bdaef16586ecd79568146c4ac4



Michael Wojtynek

unread,
Apr 3, 2015, 8:21:13 AM4/3/15
to swri-ros...@googlegroups.com

In addition I’d like to say that I’m using mostly the cartesian path function with a step size of 0.001 m for path planning.

Here´s a code snippet of my linear movement, if it takes effect on the veleocity of movement execution:

"double fraction = group.computeCartesianPath(waypoints,
0.001, // eef_step
0.0, // jump_threshold
srv.request.trajectory, true);

robot_trajectory::RobotTrajectory rt (group.getCurrentState()->getRobotModel(), "manipulator");
rt.setRobotTrajectoryMsg(*group.getCurrentState(), srv.request.trajectory);

// create a IterativeParabolicTimeParameterization object
trajectory_processing::IterativeParabolicTimeParameterization iptp;
bool success = iptp.computeTimeStamps(rt);
ROS_INFO("Computed time stamp %s",success?"SUCCEDED":"FAILED");

// Get RobotTrajectory_msg from RobotTrajectory
rt.getRobotTrajectoryMsg(srv.request.trajectory);
// Finally plan and execute the trajectory
plan.trajectory_ = srv.request.trajectory;
ROS_INFO("Visualizing plan (cartesian path) (%.2f%% acheived)",fraction * 100.0);

if (fraction == 1.0) {
group.execute(plan);
} else"
> --
> You received this message because you are subscribed to the Google Groups "swri-ros-pkg-dev" group.
> To unsubscribe from this group and stop receiving emails from it, send an email to swri-ros-pkg-d...@googlegroups.com.
> For more options, visit https://groups.google.com/d/optout.





Shaun Edwards

unread,
Apr 3, 2015, 9:48:07 AM4/3/15
to swri-ros...@googlegroups.com
There was an issue for this...see here: https://github.com/ros-industrial/universal_robot/issues/89

> To unsubscribe from this group and stop receiving emails from it, send an email to swri-ros-pkg-dev+unsubscribe@googlegroups.com.

> For more options, visit https://groups.google.com/d/optout.





--
You received this message because you are subscribed to the Google Groups "swri-ros-pkg-dev" group.
To unsubscribe from this group and stop receiving emails from it, send an email to swri-ros-pkg-dev+unsubscribe@googlegroups.com.

Felix Messmer (IPA)

unread,
Apr 3, 2015, 9:55:58 AM4/3/15
to swri-ros...@googlegroups.com
For Cartesian Planning the duration for a trajectory point is hardcoded in MoveIt!
See https://github.com/ros-planning/moveit_ros/blob/indigo-devel/move_group/src/default_capabilities/cartesian_path_service_capability.cpp#L141

Thus, it takes 0.2 seconds to for each of your 0.001 eef_steps....

(BTW, I think it's not related to your questions, but I doubt that jump_factor 0.0 is a good value....although I don't fully understand the jump_factor parameter...)
> To unsubscribe from this group and stop receiving emails from it, send an email to swri-ros-pkg-d...@googlegroups.com.

> For more options, visit https://groups.google.com/d/optout.





--
You received this message because you are subscribed to the Google Groups "swri-ros-pkg-dev" group.
To unsubscribe from this group and stop receiving emails from it, send an email to swri-ros-pkg-d...@googlegroups.com.

Daniel Solomon

unread,
Apr 4, 2015, 8:22:06 AM4/4/15
to swri-ros...@googlegroups.com
I don't know if the timestamps assigned by the Cartesian path generator matter, does the time parameterizer use the initial timestamps or start from scratch?

You should definitely consider turning up the acceleration values, as these are used by the time parameterizer. Unfortunately, there is not a good fixed value to use. The UR is power limited, and so the max acceleration is dependant on arm configuration and actual payload. You can experimentally try to determine what acceleration valuecapable allowable for your process

Also, there is a mode in the gen3 controller that allows disabling the "human-safe" control and allows slightly better speed and power characteristics. If your process allows this, it could result in fewer controller stops for high acceleration.

Daniel Solomon

unread,
Apr 4, 2015, 8:25:47 AM4/4/15
to swri-ros...@googlegroups.com
Also to Felix's point, setting jump factor to 0 disables configuration checking. I recommend having a good value here to avoid configuration flips, maybe 1.5 radians or smaller. This may need to get higher if your step size goes up. Depending on which IK you are using, it is possible to get very unexpected results otherwise.

Michael Wojtynek

unread,
Apr 8, 2015, 4:28:04 PM4/8/15
to swri-ros...@googlegroups.com

Felix, thank you for your contribution. The function and line you marked in this cartesian service makes sense for the speed of the motion execution. I played around this value (made it bigger than 1.0 and very small like 0.001), but it hadn’t any effect on the execution speed.
If I’m using bigger eef_steps like 0.01 meters, the execution is much faster, because the cartesian function generates less trajectory points with the same step time of 0.2 from line #141. But at least I’d like to keep the eef_step size on 0.001 meters for higher accuracy.

> For Cartesian Planning the duration for a trajectory point is hardcoded in
> MoveIt!
> See
> https://github.com/ros-planning/moveit_ros/blob/indigo-devel/move_group/src/default_capabilities/cartesian_path_service_capability.cpp#L141
>
> Thus, it takes 0.2 seconds to for each of your 0.001 eef_steps....

>
> (BTW, I think it's not related to your questions, but I doubt that
> jump_factor 0.0 is a good value....although I don't fully understand the
> jump_factor parameter...)
>
>
>
>
> >

Michael Wojtynek

unread,
Apr 8, 2015, 4:51:43 PM4/8/15
to swri-ros...@googlegroups.com

Could you please describe the unexpected results of configurations flips?
At the moment I don’t understand the full matter of the jump factor.

I have raised the acceleration inside the moveit config (joint_limits.yaml). It worked out to move the robot much faster. But the ur_driver tells me a warning that the goal of the trajectory wasn’t reached, because the execution time exceeded (‘Trajectory time exceeded and current robot state not at goal, last point required’).

I was able to lower the warnings from ur_driver by setting up jump values like 2.35 or 1.57 for different types of motions (motions like cartesian moving with changing the orientation of the eef). But for some motions the jump value prevented the cartesian function to compute a trajectory. The results of these calculations were fraction values like 10-30%. Without jump factor I got for the same motion fraction results of 100%.

Daniel Solomon

unread,
Apr 9, 2015, 10:15:39 PM4/9/15
to swri-ros...@googlegroups.com
The jump factor describes how much the arm joint angles can change between each successive step. Trying to move linearly through certain arm configurations can cause the joints to rapidly flip around - these configurations are often referred to as singularities. Setting a smaller jump factor ensures that the arm configuration doesn't change more than expected between each step of the planner.

If the planner is not able to compute a path with a step size of .001 and 2.0 radians of allowable motion for that step, that means that either A. You are moving near a singular arm configuration or B. the inverse kinematics routine is delivering unexpected results.

The UR has a cylindrical singularity zone centered on axis 1, are you moving close to that area?
Reply all
Reply to author
Forward
0 new messages