Newton-Euler Equations in General Coordinates
Newton-Euler Equations in General Coordinates
Newton-Euler Equations in General Coordinates
Abstract
For the computation of rigid body dynamics, the Newton–Euler equations represent
a crucial relation unifying the laws of motion by Newton and Euler using the language
of instantaneous screws. Typically, Newton–Euler equations are stated in spatial or in
body coordinates, respectively. In this paper, a general formulation of Newton–Euler
equations is provided for arbitrary reference systems. In particular, the general form
unifies the known equations in spatial and body coordinates. To the best of the authors’
knowledge, this relation between the spatial and the body form has not been reported
in literature. The novel formulation is based on the concept of time differentiation with
respect to moving reference systems.
1. Introduction
Newton’s second law of motion states that the force f which acts upon a translating
particle, a zero-dimensional body, is proportional to the time derivative of the particle’s
linear momentum h = m · v with mass m and velocity v, all measured in an inertial sys-
tem. In Euler’s formulation (Oliveira, 2007), this is expressed in the differential equation
d d d
f= dt (h) = dt (M · v) = M · dt (v) =M ·a. (1.1)
d
Here, a = dt (v) denote the the acceleration vector and the mass matrix M = m · I
with identity matrix I = I 3 is introduced for sake of formal consistency with Euler’s
second law of motion, below. Euler’s second law of motion states that the torque τ
which acts upon a rotating body is proportional to the time derivative of the body’s
angular momentum λ = M3 · ω with inertia matrix M3 and pseudovector ω denoting
the body’s angular velocity, all measured in an inertial system. This is expressed in the
differential equation
d d d d
τ = dt (λ) = dt (M3 · ω) = dt (M3 ) · ω + M3 · dt (ω) . (1.2)
d d
The angular acceleration is denoted by α = dt (ω). The derivative dt (M3 ) is given within
the appendix. While the mass in Newton’s law is assumed to be a ‘universal’ quantity
(Ardema, 2005), the inertia of the moving body changes with respect to the inertial
system, so that the chain rule is applied in the differentiation of Euler’s law. In this
paper, the Newton–Euler equations – that subsume Equations 1.1 and 1.2 by means of
twists and wrenches – are formulated with respect to an arbitrary reference system.
The remainder of the paper is structured as follows: necessary quantities and their
notation are introduced in the next section. In Section 3, the generalized formulation
of the Newton–Euler equations is given and interrelations to corresponding formulations
in spatial and in body coordinates are discussed. In Section 4, a conclusion is drawn.
Technical computations of time derivatives are compiled in Appendix A.
IMA Conference on Mathematics of Robotics
9 – 11 September 2015, St Anne’s College, University of Oxford
2. Prerequisites
2.1. Poses and displacements
A pose matrix P ∈ R 4×4
has the form P = E0P p1 with attitude E P ∈ SO(3) and
position p ∈ R3 . A trajectory is a sorted (t)
set of poses P with t > 0. A displacement
4×4 R t
matrix D ∈ R has the shape D = 0 1 with rotation R ∈ SO(3) and translation
t ∈ R3 . The matrix D = D P Q = P −1 · Q describes the passive displacement between two
poses P ∈ SE(3) and Q∈ SE(3).The adjoint representation D Ad = Ad(D) ∈ R6×6 of
D has the shape D Ad = t ×RR R 0
.
ξ~ : p 7→ µ + ν × p .
The vector field ξ~ is characterized by the constitutive equation (Minguzzi, 2013)
ξ~ p − ξ~ q = ν × (p − q) ,
(2.1)
PREREQUISITES 3
Reference systems. For arbitrary reference systems, P ∈ SE(3) and Q ∈ SE(3), the
homogenized coordinates x1 ∈ R4 of a point X are characterized with the ‘fundamental
Similarly, the identity is stated for the representing matrices of a pose X ∈ SE(3) as
X = X O =I · X O =P · X P =Q· X Q . (2.5)
From the previous identities, the transformation rules for a coordinate change are de-
duced; for a pose matrix X, for example, as [X]P = P −1 · Q · [X]Q = D P Q · [X]Q , and
analogously, for the homogenized coordinates x1 of a point.
Evaluation points. The evaluation of the screw vector fields ξ, ~ V ~ , and W~ , which are
specified by the difference Equations 2.1,
2.2, and 2.3, read with the introduced notation
as [µ]PO = µP = ξ~ p , [v]PO = v P = V
~ p , and [τ ]PO = τ P = W
~ p .
The fundamental identities for a screw, corresponding to Equations 2.4 and 2.5, are
ν
given for its matrix representation ξ ⊗ , its Plücker vector ξ = µ , and its adjoint repre-
sentation ξ ad as
O O P Q
ξ ⊗ = ξ ⊗ O = I · ξ ⊗ O · I −1 = P · ξ ⊗ P · P −1 = Q · ξ ⊗ Q · Q−1 , (2.6)
O Ad
O Ad
P Ad
Q
ξ= ξ O=I · ξ O=P · ξ P =Q · ξ Q, (2.7)
O P Q
ξ ad = ξ ad O = P Ad · ξ ad P · (P −1 )Ad = QAd · ξ ad Q · (Q−1 )Ad . (2.8)
From these identities, transformation rules for a change of reference Psystem and eval-
uation point can be deduced. As an example, the matrix twist ξ ⊗ P with respect to
Q
the reference P , is obtained from the matrix twist ξ ⊗ Q with respect to the reference
Q as [ξ ⊗ ]PP = D P Q · [ξ ⊗ ]Q −1
Q · D P Q . With the convention [D]P Q = D P Q , the notation of
PQ
the transformation rule can be refined for two specific cases. For coinciding evaluation
points, the matrix D = ( R 0 QQ
0 1 ) is denoted as [D]P Q = D, so that the transformation
⊗ Q ⊗ Q
reads [ξ ]P = [D]P Q · [ξ ]Q · ([D]P Q ) . Similarly, for coinciding attitudes, the displace-
QQ QQ −1
Motion laws. By means of the notation [•]atref , Newton’s law of motion from Equation 1.1,
d
is rephrased as [f ]PO = M · [ dt (v)]PO where P denotes the position of the particle. Euler’s
d d
law of motion from Equation 1.2 is rephrased as [τ ]CO = [ dt M3 ]CO · ω + [M3 ]CO · dt (ω) where
C denotes the center of mass and O is chosen coincident to C. Thus, the notation proves
helpful to emphasize the feasibility constraints that underlie these two motion laws.
† If the evaluation point coincides with the origin of the reference system, it can be omitted.
IMA Conference on Mathematics of Robotics
9 – 11 September 2015, St Anne’s College, University of Oxford
Figure 1. Sketch of a moving body B, together with a moving reference system P and the
inertial system O. For simplification, the orientations E (t) (t)
P and E E are assumed to be constant
over time t. The absolute velocities, v OB of body B and v OP of observer P , are indicate by red
and green arrows. The relative velocity v P B is computed as the difference v P B = −v OP + v OB
and is indicated by blue arrows.
For an arbitrary evaluation point X, the rotative inertia matrix [M3 ]X C is determined
by the Huygens–Steiner theorem, also known as the parallel axis theorem (Selig, 2005).
With respect to an arbitrary reference system E ∈ SO(3), the rotative inertia matrix
−1
E is computed as [M3 ]E = REC · [M3 ]C · REC .
[M3 ]X X X
6×6
The affine inertia matrix M6 ∈ R subsumes the rotative inertia M3 ∈ R3×3 and
the translative mass M = m · I. At the center of mass C, the affine matrix [M6 ]CC has the
C [M3 ]C 0
shape M6 C = 0
C
M
. With respect to an arbitrary reference system P ∈ SE(3),
the spatial inertia matrix [M6 ]PP is computed via the skew axis theorem (Selig, 2005)
P −T
C −1
M6 P = (D Ad PC) · M6 C · (D Ad
PC) , (2.9)
a generalized version of the Huygens–Steiner theorem. As in Section 2.3, refined state-
ments can be made in case of coinciding evaluation points or reference attitudes. In case
that D only changes the evaluation point, D = ( 0I 1t ), or the reference system D = ( R 0
0 1 ),
PC PP
the formulation can be refined by denoting D as D = [D]CC , or as D = [D]P C , respec-
tively. By means of the screw swap operator 4 the first factor (D Ad PC)
−T
in Equation 2.9
Ad −T
is alternately expressed as (D P C ) = 4 · (D P C ) · 4. The fundamental identity for
Ad
[ x1 ]P , [ dt
d
d x ⊗ x
In a physical interpretation, the three terms dt 1 ]P , and [V P · 1 ]P
describe the relative velocity of X with respect to P , the absolute velocity of X with
respect to O, and the absolute velocity of P with respect to O and evaluated at X;
IMA Conference on Mathematics of Robotics
9 – 11 September 2015, St Anne’s College, University of Oxford
A GENERAL FORMULATION 5
3. A general formulation
3.1. Newton–Euler equations in general coordinates
The Newton–Euler equations in general coordinates state that the wrench W which
acts upon a moving body at a point X fixed in the lamina of the non-inertial reference
system P is proportional to the time derivative of the body’s momentum 4·M6 ·V , both
expressed with respect to the reference P . This is expressed by the differential equation
h iX h iX
d
W = dt 4 · M6 · V . (3.1)
P P
d
X ad T X
M6 O = (− ω
Here, the time derivative of the spatial inertia matrix, dt v ) · M6 O +
X ad
M6 O · − ω
v from Equation A 3 in the appendix is used together with the identity
IMA Conference on Mathematics of Robotics
9 – 11 September 2015, St Anne’s College, University of Oxford
The equations are stated in this form, for example, by Featherstone, 2008.
Body coordinates. With respect to a reference system B moving together with the body,
d X
the first summand dt 4 · M6 · V P of Equation 3.2 is simplified by using the time
d
X X d ω X X
4 · M6 · ω
invariance of the body inertia, dt v B
= 4 · M6 B · dt v B
= 4 · M6 B ·
α X
a B
. Thus, Equation 3.2 simplifies to
h iX h iX h iX h ad T iX h iX h iX
α ωB ω
W = 4 · M6 · a
+ − v
· 4 · M6 · v
. (3.4)
B B B B B B B
For the case that the evaluation point X coincides with the center of mass C, Equation 3.4
covers
iC h iC h iC C
τ α
h
[M3 ]C 0 [ω]B × [M3 ]C C
B · [ω]B 0
4·W = f
= 0
B
M
· a
+ 0 C
[ω] × M · [v] C .
B B B B B
The Newton–Euler equations are stated in this form, for example, by Murray et al., 1994,
and by Fossen, 2011.
General coordinates. For the case of an arbitrarily moving reference frame P , the general
Newton–Euler equations of Equation 3.2 read in components
h iX iX h ad iX h iX
f ω ωP ω
h
d
τ = dt 4 · M 6 · v + v
· 4 · M6 · v . (3.5)
P P P P P
4. Conclusions
This paper provides a general formulation of the Newton–Euler equations obtained by
differentiation with respect to non-inertial reference systems and by using a suitable
notation scheme. The general equations unify the known formulations in spatial and in
body coordinates and clarify their interrelation. The derived connection can simplify
communicating mechanics of rigid bodies. Additionally, the novel formulation of the
Newton–Euler equations might prove applicable to questions arising in computational
rigid body mechanics with regard to moving reference frames. In robotics, for example,
mobile reference systems are of interest when the interaction of a robot’s end-effector
link with the robot’s environment is required to be described from the point of view of
another moving link of the mechanical device.
Acknowledgments. The work presented in this paper was funded by the Federal Ministry of
Education and Research (BMBF) within the project Recupera (Grant 01-IM-14006A).
IMA Conference on Mathematics of Robotics
9 – 11 September 2015, St Anne’s College, University of Oxford
APPENDIX 7
Twists. The time derivative of atwist V with respect to the inertial reference system O
is denoted by A = α d ω d
a = dt v = dt (V ).
Inertia matrices. The time derivative of spatial inertia matrix M6 with respect to the
inertial reference system O is
d d
O d O ad T
O O ad
dt (M6 ) = dt M6 O = dt M6 O = −(V ) · M6 O − M6 O · V . (A 3)
The equation is obtained by the transformations (using Equation 2.10, the chain rule,
and identities from Equation A 2)
d d
O d O d Ad −T
B −1
dt (M6 ) = dt M6 O = dt M6 O = dt (D OB ) · M6 B · (D Ad
OB )
d −T
B −1 −T
B d −1
= dt (D Ad
OB ) · M6 B · (D Ad
OB ) + 0 + (D Ad
OB ) · M6 B · dt (D AdOB )
−T
B −1 −T
B −1
= (−V ad
OB )
T
· (D Ad
OB ) · M6 B · (D Ad
OB ) + (D Ad
OB ) · M6 B · (D Ad
OB ) · (−V adOB )
ad T
B B ad
= −(V OB ) · M6 B − M6 B · V OB .
A.2. General time derivatives
Poses. The time derivative of a pose matrix X = X (t) with respect to a mobile reference
system P with matrices P = P (t) is obtained in analogy to Equation 2.11 as
d −1
d d
d
dt X P = P · dt X O = P −1 · dt X O = P −1 · dt P· X P
d d
= P −1 · dt (P ) · X P + P · dt X P
d
⊗
= dt X P + V P P · X P .
In the first line, the ‘fundamental identity’ Equation 2.5 is applied twice. In addition,
the invariance of the inertial system is used. Next, the chain rule is applied. In the third
d
line, the expression is expanded, simplified by using P −1 · dt (P ) = V P⊗ P , and sorted.
The computation principle remains in the following derivations.
Screws. The time derivative of a screw matrix ξ ⊗ = (ξ ⊗ )(t) with respect to a mobile
reference system P with matrices P = P (t) is computed as
d ⊗ d ⊗ d
⊗ d
dt ξ P = P
−1
· dt ξ O · P = P −1 · dt ξ O · P = P −1 · dt P · ξ ⊗ P · P −1 · P
d
⊗ P d
d
= dt ξ P + P −1 · dt (P ) · ξ ⊗ P + ξ ⊗ P · dt (P −1 ) · P
d
⊗ P ⊗ ⊗ P ⊗ P ⊗
= dt ξ P + VP P · ξ P − ξ P · VP P .
IMA Conference on Mathematics of Robotics
9 – 11 September 2015, St Anne’s College, University of Oxford
The fundamental identity of Equation 2.6 is applied in the first line. For thesimplification,
d d d
the identity dt (P −1 ) · P = (−P −1 · dt (P ) · P −1 ) · P = −P −1 · dt (P ) = − V P⊗ P is used.
In Plücker coordinates, the corresponding expression reads
d P d
P ad P
dt ξ P = dt ξ P + V P P · ξ P . (A 4)
Inertia matrices. The time derivative of an inertia matrix M6 = M6(t) with respect to a
mobile reference system P with matrices P = P (t) is
d P d
P ad T P P ad
dt M6 P = dt M6 P − ( V P P ) · M6 P − M6 P · V P P (A 5)
The equation is obtained with the identity Equation 2.10 as
d P d
O d
P
dt M6 P = (P
Ad T
) · dt M6 O · P Ad = (P Ad )T · dt (P Ad )−T · M6 P · (P Ad )−1 · P Ad
d
P d
P P d
= dt M6 P + (P Ad )T · dt (P Ad )−T · M6 P + M6 P · dt (P Ad )−1 · P Ad
d
P P P
= dt M6 P − ( V Pad P )T · M6 P − M6 P · V Pad P .
In the last transformation, the simplifications, with ⊕ inverse to ⊗, so that ξ ⊗⊕ = ξ,
d
⊕ ad
dt (P
Ad −1
) · P Ad = (P Ad )−1 · (−V Pad ) · P Ad = − (P )−1 · (V P⊗ ) · P = − V Pad P
d
T
(P Ad )T · dt (P Ad )−T = (P Ad )T (−V Pad )T (P Ad )−T = − (P Ad )−1 ·V Pad ·P Ad = −( V Pad P )T
are used. They are derived by means of the identities given in Equation A 2.
REFERENCES
Ardema, M. (2005). Newton-Euler Dynamics. Springer.
Davidson, J. K., Hunt, K. H., and Pennock, G. R. (2004). Robots and Screw Theory: Applications
of Kinematics and Statics to Robotics. Oxford University Press.
Featherstone, R. (2008). Rigid Body Dynamics Algorithms. Springer.
Fossen, T. I. (2011). Handbook of Marine Craft Hydrodynamics and Motion Control. John Wiley
& Sons.
Hunt, K. H. (2003). Don’t Cross-Thread the Screw! Journal of Robotic Systems, 20(7).
Mason, M. T. (2001). Mechanics of Robotic Manipulation. MIT Press.
McCarthy, J. M. and Soh, G. S. (2010). Geometric Design of Linkages. Springer.
Minguzzi, E. (2013). A geometrical introduction to screw theory. European Journal of Physics,
34(613).
Murray, R. M., Li, Z., and Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manip-
ulation. CRC Press.
Oliveira, A. R. E. (2007). Euler’s Contribution to Classical Mechanics. In 12th IFToMM World
Congress.
Phillips, J. (2007). Freedom in Machinery: Volume 1 (1984) and Volume 2 (1990). Cambridge
University Press.
Sathaye, A. (2011). Notes on Similarity. Lecture Notes, MA322.
Selig, J. M. (2005). Geometric Fundamentals of Robotics. Springer.
Tsai, L.-W. (1999). Robot Analysis: The Mechanics of Serial and Parallel Manipulators. John
Wiley & Sons.
Uicker, J. J., Pennock, G. R., and Shigley, J. E. (2003). Theory of Machines and Mechanisms.
Oxford University Press.
Uicker, J. J., Ravani, B., and Sheth, P. N. (2013). Matrix Methods in the Design Analysis of
Mechanisms and Multibody Systems. Cambridge University Press.