Robot dynamics
Roy Featherstone (2007), Scholarpedia, 2(10):3829. | doi:10.4249/scholarpedia.3829 | revision #91723 [link to/cite this article] |
Contents |
Definition
Robot dynamics is concerned with the relationship between the forces acting on a robot mechanism and the accelerations they produce. Typically, the robot mechanism is modelled as a rigid-body system, in which case robot dynamics is the application of rigid-body dynamics to robots. The two main problems in robot dynamics are:
- Forward dynamics: given the forces, work out the accelerations.
- Inverse dynamics: given the accelerations, work out the forces.
Forward dynamics is also known as "direct dynamics," or sometimes simply as "dynamics." It is mainly used for simulation. Inverse dynamics has various uses, including: on-line control of robot motions and forces, trajectory design and optimization, design of robot mechanisms, and as a component in some forward-dynamics algorithms.
Other problems in robot dynamics include:
- Calculating the coefficients of the equation of motion.
- Inertia parameter identification --- estimating the inertia parameters of a robot mechanism from measurements of its dynamic behaviour.
- Hybrid dynamics: given the forces at some joints and the accelerations at others, work out the unknown forces and accelerations.
Equations of Motion
The equation of motion for a robot mechanism can be written \[\tag{1} \boldsymbol{\tau} = \boldsymbol{H}(\boldsymbol{q}) \ddot{\boldsymbol{q}} + \boldsymbol{c}(\boldsymbol{q},\dot{\boldsymbol{q}},\boldsymbol{f}_{\!ext}) \,. \]
In this equation, \(\boldsymbol{q}\ ,\) \(\dot{\boldsymbol{q}}\ ,\) \(\ddot{\boldsymbol{q}}\) and \(\boldsymbol{\tau}\) are vectors of joint position, velocity, acceleration and force variables, respectively, and they are called the joint-space position, velocity, acceleration and force vectors. Each is an \(n\)-dimensional coordinate vector, where \(n\) is the number of (independent) joint variables in the mechanism. The force variables are defined such that \(\dot{\boldsymbol{q}}^\mathrm{T}\boldsymbol{\tau}\) is the power delivered by \(\boldsymbol{\tau}\) to the system. Thus, \(\dot{\boldsymbol{q}}\) and \(\boldsymbol{\tau}\) qualify as a set of generalized velocity and force variables for the system.
\(\boldsymbol{f}_{\!ext}\) denotes an external force acting on the robot, due to contact with the environment (so the robot is exerting a force of \(-\boldsymbol{f}_{\!ext}\) on the environment). Typically, \(\boldsymbol{f}_{\!ext}\) is a spatial (6D) vector describing the contact force acting on the robot's end effector. This is appropriate if the robot makes contact with its environment only through its end effector. If the robot makes multiple contacts, then it can be regarded as having multiple end effectors (e.g. the hands and feet of a humanoid robot); and \(\boldsymbol{f}_{\!ext}\) is then the concatenation of the individual contact force vectors. If there are \(N_E\) end effectors, then \(\boldsymbol{f}_{\!ext}\) is a \(6N_E\)-dimensional vector.
\(\boldsymbol{H}\) is called the joint-space inertia matrix, and it is an \(n\times{}n\) symmetric, positive-definite matrix. \(\boldsymbol{c}\) is called the joint-space bias force, which is the value of the joint-space force that must be applied to the system in order to produce zero acceleration. (The choice of symbols varies from one author to the next.) The expressions \(\boldsymbol{H}(\boldsymbol{q})\) and \(\boldsymbol{c}(\boldsymbol{q},\dot{\boldsymbol{q}},\boldsymbol{f}_{\!ext})\) indicate that \(\boldsymbol{H}\) is a function of \(\boldsymbol{q}\ ,\) but \(\boldsymbol{c}\) is a function of \(\boldsymbol{q}\ ,\) \(\dot{\boldsymbol{q}}\) and \(\boldsymbol{f}_{\!ext}\ .\) Once these dependencies are understood, they are usually omitted. Together, \(\boldsymbol{H}\) and \(\boldsymbol{c}\) are the coefficients of the equation of motion. The kinetic energy of the robot mechanism is \[ T = \frac{1}{2} \dot{\boldsymbol{q}}^\mathrm{T} \boldsymbol{H} \dot{\boldsymbol{q}} \,. \] Although \(\boldsymbol{H}\) is never singular, it can be highly ill-conditioned.
Equation () is the most useful for calculation purposes. However, there are two other ways to write the equation of motion that are useful for robot control systems. The first is \[\tag{2} \boldsymbol{\tau} = \boldsymbol{H}(\boldsymbol{q}) \ddot{\boldsymbol{q}} + \boldsymbol{C}(\boldsymbol{q},\dot{\boldsymbol{q}}) \dot{\boldsymbol{q}} + \boldsymbol{\tau}_{\!g}(\boldsymbol{q}) + \boldsymbol{J}(\boldsymbol{q})^\mathrm{T} \boldsymbol{f}_{\!ext} \,, \]
in which the bias force has been broken into its component parts. The term \(\boldsymbol{C}\dot{\boldsymbol{q}}\) includes the Coriolis and centrifugal forces, and it is the product of a square matrix \(\boldsymbol{C}\) with the vector \(\dot{\boldsymbol{q}}\ .\) Gravity terms are included in the vector \(\boldsymbol{\tau}_{\!g}\ ;\) and the effect of the external force is given by \(\boldsymbol{J}^\mathrm{T}\boldsymbol{f}_{\!ext}\ .\) The matrix \(\boldsymbol{J}\) is the Jacobian of the end effector (or set of end effectors). It satisfies the equation \[ \boldsymbol{v}_{ee} = \boldsymbol{J} \dot{\boldsymbol{q}} \,, \] where \(\boldsymbol{v}_{ee}\) is the spatial (6D) velocity of the end effector, or the concatenation of the spatial velocities of the end effectors, if the robot has more than one. Thus, \(\boldsymbol{J}\) is a \(6N_E\times{}n\) matrix.
The second alternative form for the equation of motion is called the operational-space formulation. It expresses the dynamics in the robot's task space, which is the space in which the robot is commanded to operate. Typically, the task space is the space of positions and orientations of the end effector. The operational-space formulation is written \[ \boldsymbol{\Lambda}(\boldsymbol{x}) \dot{\boldsymbol{v}} + \boldsymbol{\mu}(\boldsymbol{x},\boldsymbol{v}) + \boldsymbol{\rho}(\boldsymbol{x}) = \boldsymbol{f} \,, \]
where \(\boldsymbol{x}\) is a vector of position coordinates, \(\boldsymbol{v}\) is a spatial vector giving the end-effector's velocity, \(\boldsymbol{f}\) is the spatial force acting on the end effector, and \(\boldsymbol{\Lambda}\ ,\) \(\boldsymbol{\mu}\) and \(\boldsymbol{\rho}\) are the coefficients of the equation of motion. \(\boldsymbol{\Lambda}\) is called the operational-space inertia matrix; \(\boldsymbol{\mu}\) contains Coriolis and centrifugal force terms; and \(\boldsymbol{\rho}\) contains gravity terms. \(\boldsymbol{f}\) is the sum of an external force acting on the end effector and the projection onto the end effector of the actuator forces acting at the joints.
Dynamic Models
Strictly speaking, the coefficients of Eq () do not depend only on \(\boldsymbol{q}\ ,\) \(\dot{\boldsymbol{q}}\) and \(\boldsymbol{f}_{\!ext}\ ,\) but also on the dynamic model of the robot mechanism. This is a description of the mechanism in terms of its component parts: bodies, joints, and the parameters that characterize them. Specifically, a dynamic model consists of the following:
- a kinematic model of the robot mechanism, and
- a set of inertia parameters.
Ten inertia parameters are required to define the inertia of a single rigid body (mass, location of center of mass, and six rotational inertia parameters); so a dynamic model will normally contain 10 inertia parameters per body. However, when bodies are connected together to form a mechanism, they lose some of their degrees of motion freedom. As a result, some of their inertia parameters may have no effect on the dynamic behavior of the system, or may be indistinguishable from algebraic combinations of other inertia parameters. Therefore, if the task is to obtain a dynamic model of a robot mechanism from a given kinematic model and a set of measurements of its dynamic behavior, then the procedure is to identify the values of a set of base inertial parameters, which are the set of observable inertia parameters of the system (Khalil and Dombre, 2002).
Dynamics Algorithms
There are three main algorithms used in robot dynamics:
- The recursive Newton-Euler algorithm (RNEA). This algorithm solves the inverse dynamics problem, and has a computational complexity of \(O(n)\ .\) It can also be used to calculate \(\boldsymbol{c}\) in Eq (); and it can be modified so as to calculate the terms \(\boldsymbol{C}\dot{\boldsymbol{q}}\) and \(\boldsymbol{\tau}_{\!g}\) in Eq ().
- The articulated-body algorithm (ABA). This algorithm solves the forward dynamics problem, and has a computational complexity of \(O(n)\ .\)
- The composite-rigid-body algorithm (CRBA). This algorithm calculates the joint-space inertia matrix, \(\boldsymbol{H}\ ,\) and has a computational complexity of \(O(n^2)\ .\) When combined with the RNEA, to calculate \(\boldsymbol{c}\ ,\) and a linear equation solver, to solve \(\boldsymbol{H}\ddot{\boldsymbol{q}}=\boldsymbol{\tau}-\boldsymbol{c}\) for \(\ddot{\boldsymbol{q}}\ ,\) the result is an algorithm to solve the forward dynamics problem having a computational complexity of \(O(n^3)\ .\) Although this algorithm will inevitably be slower than the ABA for sufficiently large values of \(n\ ,\) the two algorithms have approximately the same efficiency at small values of \(n\ ,\) such as \(n=6\ .\)
To give rough ballpark figures for the efficiencies of these algorithms, the RNEA requires about 200 floating-point calculations per body, the ABA requires about 450 per body, and the CRBA requires about \(16n^2\) to calculate an \(n\times{}n\) inertia matrix. The cost of the CRBA varies according to how the bodies are connected together, being substantially cheaper for a branched tree than for a long chain. Source code for these algorithms can be found on Featherstone's spatial vectors page, and descriptions can be found in (Featherstone, 1987, 2007; Featherstone and Orin, 2000; Siciliano and Khatib, 2008).
Fixed and Floating Bases
A robot is said to have a fixed base if it is rigidly attached to a fixed support. An industrial robot arm is a good example of a fixed-base robot. If no part of the robot mechanism is fixed, then it is said to have a floating base. Wheeled and legged mobile robots, flying robots, swimming robots and humanoids are all floating-base robots. In a floating-base robot, one particular link is identified as the floating base. Usually, it is the largest or heaviest link.
The standard versions of the three dynamics algorithms calculate the dynamics of a fixed-base robot, but the ABA can be modified trivially to calculate the dynamics of a floating-base robot. The other two algorithms can be adapted as follows. Starting with the dynamic model of the floating-base robot, introduce a fictitious fixed base, and connect it to the floating base via a fictitious joint having six degrees of freedom (a 6-DoF joint). Such a joint does not impose any motion constraints on the floating base, and therefore does not alter the dynamics of the floating-base robot. The modified dynamic model now has a fixed base and six additional joint variables, the latter serving to define the position and orientation of the floating base. As the modified system does now have a fixed base, the RNEA and CRBA can be applied directly to it.
Inverse Dynamics and Floating Bases
The RNEA expects to be told all of the joint accelerations, so that it can work out all of the forces. If the RNEA is applied to the modified dynamic model, then it expects to be told the acceleration of every real joint, and also the acceleration of the fictitious 6-DoF joint (i.e., it wants to know the acceleration of the floating base). If this acceleration is not known, then the problem is no longer an inverse-dynamics problem, but a hybrid-dynamics problem: the acceleration variables of the real joints and the force variables of the 6-Dof joint (which are zero) are given, and the task is to calculate the unknown forces at the real joints and the unknown acceleration of the floating base. All three dynamics algorithms can be adapted to solve hybrid-dynamics problems.
Loops and Trees
The connectivity of a robot mechanism can be described using a graph in which the nodes represent the bodies and the arcs represent the joints. If this graph does not contain any cycles, implying that it is a topological tree, then the robot mechanism is called a kinematic tree. Furthermore, if the tree does not contain any branches, then it can be called a kinematic chain. All three dynamics algorithms work on kinematic trees.
If the connectivity graph does contain cycles, then the robot mechanism contains kinematic loops, and is called a closed-loop system. The three dynamics algorithms described above do not work on closed-loop systems, although they can be used as components in a closed-loop dynamics algorithm. In general, closed-loop systems have more complicated dynamics than kinematic trees, and they require more sophisticated (and expensive) algorithms to calculate their dynamics.
References
Featherstone, R., and Orin, D. E. (2000). Robot Dynamics: Equations and Algorithms. IEEE Int. Conf. Robotics and Automation, pp. 826-834.
Khalil, W., and Dombre, E. (2002). Modeling, Identification and Control of Robots. New York: Taylor and Francis.
Internal references
- Olaf Sporns (2007) Complexity. Scholarpedia, 2(10):1623.
- James Meiss (2007) Dynamical systems. Scholarpedia, 2(2):1629.
- Eugene M. Izhikevich (2007) Equilibrium. Scholarpedia, 2(10):2014.
Recommended Reading
Featherstone, R. (1987). Robot Dynamics Algorithms. Boston: Kluwer Academic Publishers.
Featherstone, R. (2007). Rigid Body Dynamics Algorithms. Boston: Springer.
Siciliano, B., and Khatib, O. (eds.) (2008). Springer Handbook of Robotics. Berlin: Springer.
See Also
(links to be added later)