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

Planning complex plans using multiple waypoints with MoveIt

asked 2017-05-09 05:04:14 -0500

Matziieee gravatar image

Hi,

I am currently doing a school project where we were given the task to "simulate" a welding path using a UR5. Since the welding path has to be very precise we have created a path containing around 700 waypoints that the arm has to go through. Initially we tried simply defining every single pose using Eigen::Affine3d and Eigen::Quaterniond, for instance this is our first waypoint.

Eigen::Affine3d pose1= Eigen::Translation3d(0.618794, 0.02779, 0.1482) * Eigen::Quaterniond(0.4815, 0.1315, -0.8665, 0);

Following defining all 700 of these poses we would simply do

group.setPoseTarget(pose1);
group.move();
group.setPoseTarget(pose2);
group.move();

and so on.

Now this probably has a number of disadvantages, but the most apparent one is that when running this program on a real UR5, the motors stop after every group.move which means that there is a LOT of stuttering.

My question is:

Is there a way to compute a path with all of these waypoints included? And can this path then be executed in one fluid motion? If this is not possible using MoveIt, is there another way to do it within ROS? We really want to use ROS for this, but watching other groups use "simple" simulation software to execute their paths is rather disheartening and makes us want to go for the "easy" solution.

We are currently running ROS Indigo on Ubuntu 14 using ROS Industrial for simulation and the Modern UR driver for when connecting to the UR5.

Any help is appreciated and please tell me if i need to explain anything further.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
8

answered 2017-05-09 06:56:22 -0500

gvdhoorn gravatar image

updated 2019-03-11 07:17:17 -0500

This is certainly possible, but as you found out, group.move() is probably not the best way to do this: group.move() assumes that you want to move your EEF, while avoiding collisions, through an unstructured / semi-structured scene to a single destination. That requires motion planning, which is a (relatively) complex process. On top of that, each .move() is considered a separate request, with smoothness only 'guaranteed' between start and goal of the motion, not between subsequent requests. The fact that you submit a lot of goals, one after the other, does not make MoveIt 'realise' that you want something it isn't doing: you're sending it separate requests, so MoveIt generates a lot of (very short) trajectories for you, just as you ask.

This is where your 'stuttering' is coming from.

The "simple" simulation software that you are referring to is probably either a CAD-to-path (c2p) or a kinematic playout tool (RoboDK by any chance?), not a simulation per se. These essentially generate either a single motion through all waypoints, or use something called blending to make subsequent motions smoothly follow each other. This blending is typically done by the controller, not the software generating the robot program.

As useful as those c2p tools are, it's slightly unfair to compare what they are doing to what MoveIt is doing: the latter is a complete planning pipeline, able to deal with (almost) arbitrarily complex kinematic setups and environments, with a focus on getting your EEF to your goal pose without colliding with anything. The former typically 'only' do pose interpolation based on waypoints generated from workpiece geometry without any regard for your robot, your tool or your environment (this is changing though).

Getting a single, continuous path out of MoveIt is possible however: you could take a look at the Cartesian Path capabilities which essentially allow you to provide a list of waypoints and plan (really: iterate) through all of them at once. See Move Group Interface Tutorial - Cartesian Paths for an impression on how to do this.

Another option would be to look at a planner such as Descartes: that is a slightly different approach, but well suited for these type of tasks. There is currently some interest over at the ROS-Industrial mailing list to extend the tutorials of Descartes with some more info on how it could be used for something like welding. See Descartes path planning extra tutorial.


Note btw that to successfully weld something you would most likely also need synchronised (de)activation of your EEF / other peripherals. Neither MoveIt nor Descartes will do this for you. Good welding is actually not trivial and includes much more than just planning a smooth motion through a nr of waypoints.

edit flag offensive delete link more

Comments

Thank you so much for your help. I am going to look into both Cartesian paths and Descartes and find out which i prefer. On another note I would like to thank you for everything you've done for the community in general! Your posts have already helped me multiple times and I appreciate it a lot :)

Matziieee gravatar image Matziieee  ( 2017-05-09 07:09:07 -0500 )edit

Also another question (sorry if I am nagging) can i still use my quaternions or will i have to convert them to the format used in the cartesian path tutorial?

Matziieee gravatar image Matziieee  ( 2017-05-09 07:11:38 -0500 )edit

computeCartesianPath(..) accepts a vector of geometry_msgs/Pose, so that is still a Point with a Quaternion.

gvdhoorn gravatar image gvdhoorn  ( 2017-05-09 07:16:50 -0500 )edit

Thank you. Appreciate the help a lot.

Matziieee gravatar image Matziieee  ( 2017-05-09 07:25:34 -0500 )edit

Be aware that computeCartesianPath(..) is a tricky / sensitive function in MoveIt. Success depends heavily on having a good IK solver plugin configured for your setup, and on the parameters that you give it. Don't be discouraged if at first things don't seem to work.

gvdhoorn gravatar image gvdhoorn  ( 2017-05-09 07:27:13 -0500 )edit

But for any realistic welding, I'd look at Descartes.

gvdhoorn gravatar image gvdhoorn  ( 2017-05-09 07:27:28 -0500 )edit

Hey guys, with descartes, is it possible to control the velocity in cartesian space?

pmuthu2s gravatar image pmuthu2s  ( 2018-01-06 02:40:21 -0500 )edit

This would've been better as a separate question, but to answer it here: no, Descartes is a path planner, not a trajectory generator. See ros-industrial-consortium/descartes#148 for some related discussion.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-06 05:39:05 -0500 )edit

Question Tools

6 followers

Stats

Asked: 2017-05-09 05:04:14 -0500

Seen: 6,548 times

Last updated: Mar 11 '19