Automatic path planning for robotic welding


August 24, 2021 / 60 min read

Last updated: August 30, 2021

Welding robot.

Industrial robots can be used to automate a lot of tasks on the workfloor when it comes to manufacturing of physical products. Often however, it only makes economic sense to automate the most repetitive tasks in the manufacturing of large batches of similar products. One reason for this is that the movement paths of the robot need to be manually programmed by a person, a robot programmer. This programming can be time consuming and requires the necessary technical know-how. If a company would like to produce many different batches of products, or even many different unique products, many different robot programs would have to be made. This is partially simplified, as the robot program can be made to adapt automatically to external parameters, like the width and height of the product for example. But let's omit this option for now, as increasing the number program parameters usually also increases the complexity of the software, and thus the development time. This leads to the same problem: for small batches of products, or unique products, a large overhead in the production cost is created because of the necessity to manually program the robot. Imagine for a moment that the programming step can be skipped, and the robot could be programmed automatically using information from the product, like a CAD design. This would enable companies to adopt industrial robots for use in production, no matter how small the batch. The Descartes path planning algorithm is one approach to try to tackle this problem of automating the generation of movement paths for industrial robots.

Many processes can be automated with industrial robots like sanding, deburring, CNC-milling, 3D printing, etc. Here we focus on robotic arc welding, but the same principles could be applied to other manufacturing steps.

The rest of this post tries to explain the working of the Descartes algorithm, show some practical examples, and compares some of the benefits and disadvantages. In case you happen to be interested in a more thorough explanation, extra information can be found in the corresponding thesis and publication.

If you don't care about how it was done and rather just see the results, go to the results section.

Note: in the coming sections, the ”Descartes software package” will be referred to as ”Descartes”.

The type of data Descartes starts of with are the so-called trajectory points. First, the different types of trajectory points that the software uses, are discussed. Then we delve deeper into the path generation itself. Finally, we answer the question: "how are the different trajectory points used to construct a searchable graph?"

To generate a trajectory, Descartes expects multiple so-called trajectory points as input. Each trajectory point can be visualized as a translated and rotated frame in space. Trajectory points are a 6 dimensional data structure, containing 3 translations, following the x, y and z axes, and 3 euler rotations. These frames are visualized with three arrows in a right-handed orientation: the xx-axis being red, the yy-axis being green, and the zz-axis being blue.

Implicit euler rotations.

Example of how a frame can be rotated in space using implicit euler rotations.

A tool-frame is also defined, being attached to the end-effector (tool) of the robot:

Tool with frame.

A welding torch with its corresponding tool frame.

The idea is that the tool-frame is going to coincide with every trajectory point. Each trajectory point thus defines exactly one position in space of the end-effector of the robot. However, a defined position in space for the tool does not mean that the whole positioning of the robot is defined. There can in fact be multiple possible robot positions that result in the same endpoint:

Multiple possible robot positions for one tool pose.

Two different robot positions are shown, where the tool (the welding torch) is located in exactly the same position and orientation in relation to base of the robot.

These different robot positions for a specific pose of the tool are called inverse-kinematic-solutions (IK-solutions). Different algorithms exist to try to come up with the different IK-solutions for a tool pose. These are called inverse kinematic solvers (IK-solvers), but we're not going into those details now. The main idea to grasp here is that for any trajectory point there can be many different robot positions that satisfy putting the tool in that position. This leads to one of the main problems that Descartes has to solve, namely: how do we decide which robot position to choose for a certain trajectory point? Imagine for a moment a series of trajectory points:

Multiple trajectory points in a straight line.

Multiple trajectory points in a straight line.

We want to make the robot move through all of these positions, so we use the IK-solver to generate solutions for each of these points. Let's suppose that each of these points has 4 possible IK-solutions. Which one do we choose for each point? If we don't choose intelligently, this can result in large movements of the robot for adjacent trajectory points:

Not choosing IK solutions well leads to sudden large movements.

Not choosing IK solutions well leads to sudden large movements.

Solving this problem leads us to the next section.

To generate a movement that goes through all of the trajectory points, a choice needs to be made in regard to the different IK-solutions. For every trajectory point, one of its solutions needs to be chosen in order to generate a complete path. To be able to make this choice, Descartes generates a graph. This graph consists of the different IK-solutions for every trajectory point (the IK-solutions are the vertices). These joint solutions are connected to every joint solution of the next trajectory point with an edge. The edges have a weight assigned, which can be calculated in function of the two joint solutions they connect.


Trajectory pointsIK-solverEdge generationJoint solutions

Steps to construct a graph from trajectory points.


The edge weight is a real number calculated by the so-called cost function. These edge weights allow the graph to be searched by an algorithm to find the path through the graph with the lowest cost. That is, the trajectory with the smallest sum of the edge weights it traverses.


Illustrated graph, with chosen path in red.


But in order to really grasp what's going on here we're going to further explore the cost function:

By choosing the right cost function, we can influence the final IK-solutions that Descartes chooses. Let's have a look at the default cost function.

When generating its graph, Descartes generates edges, with a certain weight. This edge weight is a real number, and reflects the movement cost to go from joint position AA to joint position BB. Suppose the robot has ii amount of joints, with joint angles written as θi\theta_i, and the edge weight for a jjth trajectory point is calculated. We'll write the jjth joint position as xjx_j. The iith joint angle of the jjth trajectory point is written as θi(xj)\theta_i(x_j). Then the edge weight wjw_j is calculated as follows:

wj=1iθi(xj)θi(xj+1)w_j = \sum_{1}^{i}{\big|\theta_i(x_j)-\theta_i(x_{j+1})\big|}

The standard edge weight that Descartes uses is thus a simple sum of the differences in joint angles between different joint solutions. With a simple change of the code, Descartes allows the possibility to create custom cost functions to generate the edge weights. However, the only variables that can be used in these custom cost functions, is information that can be extracted from the two joint solutions given to the edge weight function.

By using the default cost function we can now get better trajectories, without the large jumps from point to point:

Using the cost function results in smooth trajectories.

Using the cost function results in smooth trajectories.

Something you might have missed in the above gif is that a little rectangular plate is placed in the path of the robot. While the robot gracefully evades this obstruction, it also causes a deviation from the optimal welding path in the rest of the points. Fixing this problem leads us to the next section:

Sometimes it is not required for the tool of the robot to be in an exact position in order for the robot to be able to execute its task. One of the most intuitive examples of this is when there's axial symmetry in the process step. Some examples of processes with axial symmetry include spray painting, machining or sanding with a rotary tool, and in our case, welding:

Three possible poses for the welding torch.

Three possible poses for the welding torch.

In the above illustration, the three different poses of the torch all bring the end of the torch in exactly the same position. For this trajectory point all three poses are valid, since they won't have any effect on the production process. In theory one would be able to rotate the torch in an infinite amount of positions, while still keeping the end of the torch in the same position.

Descartes allows us to define trajectory points like these by using a concept called tolerances. Tolerances can be defined around the different welding angles, allowing the tool of the robot to vary within the ranges of these tolerances. Of course we can't calculate an infinite number of IK-solutions, so these tolerances will have to be discretisized into a finite number of toleranced frames. An illustration will help clear up this concept, the following illustration has a tolerance of about 40 degrees around the xx-axis with a discretization step size of 10 degrees. This leads to 4 extra toleranced frames being generated:

Toleranced frame.

A tolerance around the x axis leads to any frame within certain ranges to be valid.

These toleranced frames (or toleranced trajectory points) all belong to a single trajectory point defined by the user. The IK-solver will try to find IK-solutions for every toleranced frame that has been generated, just like a regular trajectory point. When the graph is built, each toleranced frame is connected with an edge to every toleranced frame of the following trajectory point.

Trajectory pointsTolerancediscretizationIK-solverTolerancedframesJoint solutionsEdge generation (only one point illustrated)

Steps to construct the graph, this time including the toleranced points.


So, tolerances on different rotations and translations can be constructed by defining the necessary tolerance intervals. These tolerance intervals contain the upper and lower bounds of the corresponding rotation or translation. By using these tolerances, we can make the trajectory generation more flexible. In cases where no solutions can be found, tolerances may be used to allow certain deviations from the ideal trajectory. However, when allowing tolerances, the possible effects of the tolerances on the process have to be taken into account. In the case of robot welding, the welding torch needs to point in the general direction of the weld. Let's now have a look how these tolerances can be defined with the specific use case of arc welding in mind.

The first tolerance we may intuitively want to allow is a certain deviation of the welding torch from the optimal path by a few degrees. If the direction of this tolerance would not matter, this would ideally result in a cone-shaped tolerance, as shown in in the following figure.

Conical tolerance zone around the z-axis.

Conical tolerance zone around the z-axis.

This would mean that the zz-axis of the robot's end effector would be allowed to in any position within the cone. We approximate this shape by using two tolerances on the xx and yy euler angles.

Pyramid shaped tolerance zone around the z-axis.

Construction of a pyramid shaped tolerance zone around the z-axis.

This approach also allows us to differentiate between different tolerance angles. In this case, the angles around the x- and the y-axis. This will prove to be handy when defining our own cost function. But before we go into that, we have to understand the effects of the different welding angled on the weld quality.

In order to create a custom cost function, we need to understand the different welding angles and their effect on the weld quality. The following illustration shows the two different welding angles, the transverse angle and the push/drag angle.

Transverseangle(45°)Travel planePush angleDrag angle

Different welding angles.


The transverse angle has a stronger effect on the weld quality than the push/drag angle, and should always be close to the "half angle" between the two surfaces to be welded. Weld quality deteriorates fast when deviating from the optimal transverse angle. So it would be best to limit any deviation from this angle to a minimum. The push/drag angles mostly have an effect on the bead shape, as shown in the following figure.

Direction of travelDragPush

Effect of the push/drag angle on the bead shape.


Now that we know that the different welding angles have different effects on weld quality, let's define a cost function that generates an extra cost when the torch deviates from the optimal path. By being able to differentiate between the different xx and yy tolerance angles, we can also differentiate between the different welding angles.

We start off with the general idea that the further we deviate from the optimal trajectory point, the higher the cost.

θdeviation

Total deviation angle.


If we want to specify a different cost for the different welding angles, we also have to split this deviation angle θdeviation\theta_{deviation} into its components as rotations around the xx and yy axes. This can be done by projecting the deviating zz-axis onto the xx-zz and yy-zz planes as shown below.

Projection of the deviation into their respective planes.


By projecting the toleranced frame's zz-axis onto the xx-zz-plane of the optimal frame, the angle between this projection and a unit vector placed along the zz-axis of the optimal frame can be calculated using the dot product of these two vectors. This results in the deviation of the transverse welding angle. When projecting the toleranced frame's zz-axis onto the yy-zz-plane of the optimal frame, the angle between this projection and the unit-vector along the zz-axis of the optimal frame is the deviation of the push/drag angle.

θtransverseθpush/drag

The projected vector's angles with the z-axis are now the different welding angles.


We can now use these different angles θtransverse\theta_{transverse} and θpush/drag\theta_{push/drag} to calculate and extra cost CC:

C=c1θtransverse+c2θpush/dragC = c_1 \cdot \theta_{transverse} + c_2 \cdot \theta_{push/drag}

Where c1c_1 and c2c_2 are unique cost factors. In the case of welding, c1c_1 should be chosen larger than c2c_2 since the transverse welding angle has a larger effect on weld quality. This way the robot will first deviate by changing the push/drag angle, and only deviate from the transverse angle when absolutely necessary. The total cost now becomes:

wj=1iθi(xj)θi(xj+1)+Cj+1w_j = \sum_{1}^{i}{\big|\theta_i(x_j)-\theta_i(x_{j+1})\big| + C_{j+1}}

In essence we add the deviation cost of the toleranced frame to the weight of the edge.

Deviation costs are added to the edge weight. (Bent arrows.) The chosen path is in red.


Now why did we put in all this work?! Well, in essence, we have created an algorithm that not only automatically generates robot movements, but also automatically deviates from the optimal path when necessary. Sometimes the optimal path can't be followed because of physical obstructions, or because of singularities in the robot arm.

Let's compare some of the results.

We start off with the smooth move example. This is a movement path with an obstruction placed in the path of the robot.

Robot movement with standard cost function.

Robot movement with standard cost function.

Note that the robot deviates from the optimal accross the whole path. This is logical, since there is no incentive to limit deviations when they are not necessary. This results in paths where the welding torch will deviate from the optimal position across the whole path, simply because it is allowed to do so. This is illustrated in the following figure, the red line depicts the rotational deviation around the yy axis without an extra cost. The black line is the rotational deviation with extra cost.

Plot showing y angle deviation.

Plot showing y angle deviation.

Now let's take a look at the resulting movement with the added cost. (Black line in the above plot.)

Robot movement with customized cost function.

Robot movement with customized cost function.

Now the robot only evades the obstruction, and immediately moves back to the optimal path when it can. Pretty cool huh?