LESSON

Forces Acting On Robot Links

Transcript

Let's return to the simple two-link robot manipulator that we looked at much, much earlier in the course. When we first looked at it, we were interested in the kinematics, that's looking at the relationship between the joint angles, Q1 and Q2 and the position and orientation of the end-effector.

Now what we're going to do is to consider that these links have got masses so I have dropped on the symbols for the centre of mass of each of these links. So we think about how this works mechanically in practice: Each link has to support all of the other links that are beyond it and each link of course then is supported by all the links that are before it.

So there is mechanically a connection between the links, and the weight of one link has to be born by the link before it and the link before that and so on. Every link then exerts a force and a moment on its neighbouring links.

So a really useful way to consider the forces and moments that are acting on each of these links is to draw a free body diagram. What we do is we disconnect the different links and we look at them individually, they are free bodies.

Each link has got a mass and gravity's going to act on that mass with a downward force. The base of the robot is going to provide a vertical upward force to hold the red link up to stop it from falling down and the green link is going to provide a downward force on the end of the red link due to its own weight.

Look now at the green link, there's going to be an upward force here, which equal and opposite of the downward force on the red link. This is Newton's third law. So if there is a downward force on the red link is the weight of green link and there is a upward force on the green link which is provided by the red link to keep it up.

Now there is a moment provided by the motor which is driving joint one. It's providing a torque to stop the red link rotating. And similarly there's a torque applied to the green link by the joint two motor to stop the green link from rotating. And then there is a reaction torque, equal and opposite torque from that motor which is applied to the red link. 

So here we see, all the forces and moments that are acting on each of a link's of a robot. These forces and moments depend on the pose of each link, depend on the speed of a link and the acceleration of the link and of course, they also depend on gravity.

These forces and moments also depend on the link parameters; the actual mass of a link and its inertia and its length and so on. So let's have a look at some of these link parameters.

In kinematic parameters, we introduced much earlier in the course, and we have the link length. In this case, the length A1 from the axis of joint one to the axis of joint two. And similarly, we have the length of link two.

We introduced link coordinate frames here. Coordinate frame one is attached to the end of link one and coordinate frame two is attached to the coordinate frame of link two. And we looked at link co-ordinate frames again, much earlier when we were considering serial link manipulator kinematics.

We can also describe the position of the centre of mass with respect to the link one coordinate frame. In this case, it is a displacement of C1 in the negative X1 direction. And we also have a mass associated with a link that's the mass M1.

Then we also have an inertia. This is the inertia of the link with respect to its centre of mass and we can do the same thing for link two, the distance from the link two coordinate frame to its centre of mass and the inertia of link two with respect to its centre of mass.

So we have now quite a number of parameters associated with each of the links. For each link, we have a mass, we have a centre of mass which in the general case would be a vector described by three numbers and we have an inertia matrix. This is a 3x3 matrix and if we consider the inertia with respect to the centre of mass, that 3x3 is a symmetric matrix.

Now, a symmetric matrix, instead of having nine unique elements, its got only six unique elements. In total, we have ten parameters to describe the dynamics of each link. We have one mass, we have three translations to describe the position of the centre of mass with respect to the link coordinate frame, and we have six unique elements of the symmetric inertia matrix, with respect to the centre of mass.

So for link number one, those parameters are M1, the centre of mass is negative C1 in the X direction. The other two elements are zero, the vector R1, describes the position of the centre of mass. And in this case, it's negative C1 and the Y and Z components are equal to zero.

And we have the inertia matrix which has only got one element and that is the inertia about the Z axis. Now in this case, the Z axis is coming at us out of the page. So we have only one finite element that's IZZ1.

For link two, it looks somewhat similar. These are the dynamic parameters of each of the links, sometimes referred to as the inertial parameters of the links. When it comes to describing the dynamics of moving bodies, there are number of different approaches that we can take, one of the most common of course is Newton's second law, F = ma which relates the force applied to the body to the acceleration that experiences as a function of its mass.

For a rotating body, we can use Euler's equation which relates the torque applied to its body given by the symbol tau to its rotational inertia, J, it's angular rate, Omega, and its angular acceleration Omega dot.

A quite different approach is Lagrange's equation, which relates the kinetic, and potential energy of a body to the derivatives of the Lagrangian term, T minus V, and the derivatives of Lagrangian with respect to the generalized coordinates and the generalized velocities of the bodies in the mechanism.

We can use any of these approaches to analyze the dynamics of a serial link manipulator but in this lecture, we're going to consider the Newton-Euler method. This is a combination of Newton's law to describe translational motion and Euler's equation to describe the rotational motion.

A very simple and elegant approach to determining the dynamic motion of a serial link manipulator is what's called the recursive Newton-Euler algorithm. And I'm not going to go into all of the details here, you find it in many, many textbooks but what I'm want to do is give you an intuition for how it works.

And the first step is to determine the translational and rotational velocity and acceleration for the centre of mass of each of the links. Use Newton's law for the translational motion and we use Euler's equation for the rotational motion.

We start at the base of the robot and we work outwards, determining the translational and angular velocity for the centre of mass of each link in turn. Once we get to the end of the robot, we then work our way back inwards and then we determine the force and moment that each link exerts on the link that's closer towards the base of the robot. This method is computationally elegant and very, very efficient. 

I'm going to create a two-link robot in MATLAB. To do that, I'm going to use toolbox script mdl_twolink and that will create in the MATLAB workspace a robot object called two-link. This is an object that has great number of methods and properties and we'll start to explore some of these.

One of the first ones we're going to look at is the plot method. So for the robot object two-link, we’re going to invoke the plot method so that’s dot plot invokes the plot method on that object. And I'm going to plot it for Q1 equal to zero, and Q2 equal to zero.

And here we see the robot manipulator. Unlike the one we looked at previously which operated in the XY plane, we can see that this two-link robot is operating in the XZ plane. So gravitational acceleration which is in the Z direction is acting on the centre of mass of each of the links of this robot and will tend to pull it down to make it collapse.

And we can use the recursive Newton-Euler equation and we can, which is the rne method for recursive Newton-Euler. And I can ask, what are the torques on this robot if the joint angles are both equal to zero? So that's a situation I've just plotted.

And let's say the joints are not moving at all, so they've got zero velocity each and the joints are also not accelerating. So they've each got acceleration of zero.

It says that the torque on the first joint on Q1 is necessary to hold it in this position is 19.62 Newton meters and the torque on the second joint is 4.9 Newton meters. This makes intuitive sense to us. The torque on the shoulder joint is going to be greater than the torque on the elbow joint because the shoulder has to hold up the upper arm and the lower arm, where as the elbow joint only has to hold up the lower part of the arm.

What we don't have a handle on are the signs of these two torques, which way are they acting. So a good way to see that is to re-plot the robot using a different option which is jvek. What this shows is the access of rotation of each joint.

So if we remember our right hand rule, in order to understand the direction of a positive torque, what we do is grab the axis with our right hand, point our thumb in the direction of the arrowhead and curl our fingers around the vector to indicate the direction of positive rotation.

What we can see here then is that a positive torque of 19.6 acting on a shoulder joint is going to be a torque that's trying to lift the robot arm up, which is exactly what we would expect and similarly for joint two.

So the recursive Newton-Euler algorithm has given us the torques that are required for the robot to stay in this particular configuration with both its joint angles equal to zero and with zero joint velocity and with zero joint acceleration. These are the torques that are required for the robot to be in this configuration and not move.

Code

There is no code in this lesson.

In a serial-link manipulator arm each joint has to support all the links between itself and the end of the robot. We introduce the recursive Newton-Euler algorithm which allows us to compute the joint torques given the robot joint positions, velocities and accelerations and the link inertial parameters.

Professor Peter Corke

Professor of Robotic Vision at QUT and Director of the Australian Centre for Robotic Vision (ACRV). Peter is also a Fellow of the IEEE, a senior Fellow of the Higher Education Academy, and on the editorial board of several robotics research journals.

Skill level

Undergraduate-level engineering

This content requires an understanding of undergraduate-level engineering; for example, dynamics, classical control theory - PID, poles, zeros, probability theory - random variables and Bayes’ rule.

Undergraduate-level mathematics

This content requires an understanding of undergraduate-level mathematics; for example, linear algebra - matrices, vectors, complex numbers, vector calculus and MATLAB programming.

More information...

Rate this lesson

Average

Check your understanding

Leave a comment