pinocchio  2.6.3
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
doc/c-maths/se3.md
1 # CheatSheet: SE(3) operations
2 
3 <div class="center">
4 
5 \f$
6 \newcommand{\BIN}{\begin{bmatrix}}
7 \newcommand{\BOUT}{\end{bmatrix}}
8 \newcommand{\calR}{\mathcal{R}}
9 \newcommand{\calE}{\mathcal{E}}
10 \newcommand{\repr}{\cong}
11 \newcommand{\dpartial}[2]{\frac{\partial{#1}}{\partial{#2}}}
12 \newcommand{\ddpartial}[2]{\frac{\partial^2{#1}}{\partial{#2}^2}}
13 
14 \newcommand{\aRb}{\ {}^{A}R_B}
15 \newcommand{\aMb}{\ {}^{A}M_B}
16 \newcommand{\amb}{\ {}^{A}m_B}
17 \newcommand{\apb}{{\ {}^{A}{AB}{}}}
18 \newcommand{\aXb}{\ {}^{A}X_B}
19 
20 \newcommand{\bRa}{\ {}^{B}R_A}
21 \newcommand{\bMa}{\ {}^{B}M_A}
22 \newcommand{\bma}{\ {}^{B}m_A}
23 \newcommand{\bpa}{\ {}^{B}{BA}{}}
24 \newcommand{\bXa}{\ {}^{B}X_A}
25 
26 \newcommand{\ap}{\ {}^{A}p}
27 \newcommand{\bp}{\ {}^{B}p}
28 
29 \newcommand{\afs}{\ {}^{A}\phi}
30 \newcommand{\bfs}{\ {}^{B}\phi}
31 \newcommand{\af}{\ {}^{A}f}
32 \renewcommand{\bf}{\ {}^{B}f}
33 \newcommand{\an}{\ {}^{A}\tau}
34 \newcommand{\bn}{\ {}^{B}\tau}
35 
36 \newcommand{\avs}{\ {}^{A}\nu}
37 \newcommand{\bvs}{\ {}^{B}\nu}
38 \newcommand{\w}{\omega}
39 \newcommand{\av}{\ {}^{A}v}
40 \newcommand{\bv}{\ {}^{B}v}
41 \newcommand{\aw}{\ {}^{A}\w}
42 \newcommand{\bw}{\ {}^{B}\w}
43 
44 \newcommand{\aI}{\ {}^{A}I}
45 \newcommand{\bI}{\ {}^{B}I}
46 \newcommand{\cI}{\ {}^{C}I}
47 \newcommand{\aY}{\ {}^{A}Y}
48 \newcommand{\bY}{\ {}^{B}Y}
49 \newcommand{\cY}{\ {}^{c}Y}
50 \newcommand{\aXc}{\ {}^{A}X_C}
51 \newcommand{\aMc}{\ {}^{A}M_C}
52 \newcommand{\aRc}{\ {}^{A}R_C}
53 \newcommand{\apc}{\ {}^{A}{AC}{}}
54 \newcommand{\bXc}{\ {}^{B}X_C}
55 \newcommand{\bRc}{\ {}^{B}R_C}
56 \newcommand{\bMc}{\ {}^{B}M_C}
57 \newcommand{\bpc}{\ {}^{B}{BC}{}}
58 \f$
59 
60 ## Rigid transformation
61 
62 \f$m : p \in \calE(3) \rightarrow m(p) \in E(3)\f$
63 
64 Transformation from B to A:
65 
66 \f$\amb : \bp \in \calR^3 \repr \calE(3) \ \rightarrow\ \ap = \amb(\bp) = \aMb\ \bp\f$
67 
68 \f$ \ap = \aRb \bp + \apb\f$
69 
70 \f$\aMb = \BIN \aRb & \apb \\ 0 & 1 \BOUT \f$
71 
72 Transformation from A to B:
73 
74 \f$\bp = \aRb^T \ap + \bpa, \quad\textrm{with }\bpa = - \aRb^T \apb\f$
75 
76 \f$\bMa = \BIN \aRb^T & - \aRb^T \apb \\ 0 & 1 \BOUT \f$
77 
78 For Featherstone, \f$E = \bRa =\aRb^T\f$ and \f$r = \apb\f$. Then:
79 
80 \f$\bMa = \BIN \bRa & -\bRa \apb \\ 0 & 1 \BOUT = \BIN E & -E r \\ 0 & 1 \BOUT \f$
81 
82 \f$\aMb = \BIN \bRa^T & \apb \\ 0 & 1 \BOUT = \BIN E^T & r \\ 0 & 1 \BOUT \f$
83 
84 ## Composition
85 
86 \f$ \aMb \bMc = \BIN \aRb \bRc & \apb + \aRb \bpc \\ 0 & 1 \BOUT \f$
87 
88 \f$ \aMb^{-1} \aMc = \BIN \aRb^T \aRc & \aRb^T (\apc - \apb) \\ 0 & 1 \BOUT \f$
89 
90 
91 
92 ## Motion Application
93 
94 \f$\avs = \BIN \av \\ \aw \BOUT\f$
95 
96 \f$\bvs = \bXa\avs\f$
97 
98 \f$ \aXb = \BIN \aRb & \apb_\times \aRb \\ 0 & \aRb \BOUT \f$
99 
100 \f$ \aXb^{-1} = \bXa = \BIN \aRb^T & -\aRb^T \apb_\times \\ 0 & \aRb^T \BOUT \f$
101 
102 For Featherstone, \f$E = \bRa =\aRb^T\f$ and \f$r = \apb\f$. Then:
103 
104 \f$ \bXa = \BIN \bRa & - \bRa \apb_\times \\ 0 & \bRa \BOUT = \BIN E & -E r_\times \\ 0 & E \BOUT\f$
105 
106 \f$ \aXb = \BIN \bRa^T & \apb_\times \bRa^T \\ 0 & \bRa^T \BOUT = \BIN E^T & r_\times E^T \\ 0 & E^T \BOUT\f$
107 
108 ## Force Application
109 
110 \f$\afs = \BIN \af \\ \an \BOUT\f$
111 
112 \f$\bfs = \bXa^* \afs\f$
113 
114 For any \f$\phi,\nu\f$, \f$\phi\dot\nu = \afs^T \avs = \bfs^T \bvs\f$ and then:
115 
116 \f$\aXb^* = \aXb^{-T} = \BIN \aRb & 0 \\ \apb_\times \aRb & \aRb \BOUT\f$
117 
118 (because \f$\apb_\times^T = - \apb_\times\f$).
119 
120 \f$\aXb^{-*} = \bXa^* = \BIN \aRb^T & 0 \\ -\aRb^T \apb_\times & \aRb^T \BOUT\f$
121 
122 For Featherstone, \f$E = \bRa =\aRb^T\f$ and \f$r = \apb\f$. Then:
123 
124 \f$\bXa^* = \BIN \bRa & 0 \\ -\bRa \apb_\times & \bRa \BOUT = \BIN E & 0 \\ - E r_\times & E \BOUT \f$
125 
126 \f$\aXb^* = \BIN \bRa^T & 0 \\ \apb_\times \bRa^T & \bRa^T \BOUT = \BIN E^T & 0 \\ r_\times E^T & E^T \BOUT \f$
127 
128 ## Inertia
129 ### Inertia application
130 
131 \f$\aY: \avs \rightarrow \afs = \aY \avs\f$
132 
133 Coordinate transform:
134 
135 \f$\bY = \bXa^{*} \aY \bXa^{-1}\f$
136 
137 since:
138 
139 \f$\bfs = \bXa^* \bfs = \bXa^* \aI \aXb \bvs\f$
140 
141 Cannonical form. The inertia about the center of mass \f$c\f$ is:
142 
143 \f$\cY = \BIN m & 0 \\ 0 & \cI \BOUT\f$
144 
145 Expressed in any non-centered coordinate system \f$A\f$:
146 \f$\aY = \aXc^* \cI \aXc^{-1} = \BIN m & m\ ^AAC_\times^T \\ m\ ^AAC_\times & \aI + m \apc_\times \apc\times^T \BOUT
147 \f$
148 
149 Changing the coordinates system from \f$B\f$ to \f$A\f$:
150 
151 \f$\aY = \aXb^* \bXc^* \cI \bXc^{-1} \aXb^{-1} \f$
152 \f$ = \BIN m & m [\apb + \aRb \bpc]_\times^T \\ m [\apb + \aRb \bpc]_\times & \aRb \bI \aRb^T - m [\apb + \aRb
153 \bpc]_\times^2 \BOUT\f$
154 
155 Representing the spatial inertia in \f$B\f$ by the triplet \f$(m,\bpc,\bI)\f$, the expression in \f$A\f$ is:
156 
157 \f$ \amb: \bY = (m,\bpc,\bI) \rightarrow \aY = (m,\apb+\aRb \bpc,\aRb \bI \aRb^T)\f$
158 
159 Similarly, the inverse action is:
160 
161 \f$ \amb^{-1}: \aY \rightarrow \bY = (m,\aRb^T(^AAC-\apb),\aRb^T\aI \aRb) \f$
162 
163 Motion-to-force map:
164 
165 \f$ Y \nu = \BIN m & mc_\times^T \\ mc_\times & I+mc_\times c_\times^T \BOUT \BIN v \\ \omega \BOUT
166  = \BIN m v - mc \times \omega \\ mc \times v + I \omega - mc \times ( c\times \omega) \BOUT\f$
167 
168 Nota: the square of the cross product is:
169 \f$\BIN x\\y\\z\BOUT_ \times^2 = \BIN 0&-z&y \\ z&0&-x \\ -y&x&0 \BOUT^2 = \BIN -y^2-z^2&xy&xz \\ xy&-x^2-z^2&yz \\
170 xz&yz&-x^2-y^2 \BOUT\f$
171 There is no computational interest in using it.
172 
173 ### Inertia addition
174 
175 \f$ Y_p = \BIN m_p & m_p p_\times^T \\ m_p p_\times & I_p + m_p p_\times p_\times^T \BOUT\f$
176 
177 \f$ Y_q = \BIN m_q & m_q q_\times^T \\ m_q q_\times & I_q + m_q q_\times q_\times^T \BOUT\f$
178 
179 
180 
181 
182 ## Cross products
183 
184 Motion-motion product:
185 
186 \f$\nu_1 \times \nu_2 = \BIN v_1\\\omega_1\BOUT \times \BIN v_2\\\omega_2\BOUT = \BIN v_1 \times \omega_2 + \omega_1 \times v_2 \\ \omega_1 \times \omega_2 \BOUT \f$
187 
188 Motion-force product:
189 
190 \f$\nu \times \phi = \BIN v\\\omega\BOUT \times \BIN f\\ \tau \BOUT = \BIN \omega \times f \\ \omega \times \tau + v \times f \BOUT \f$
191 
192 A special form of the motion-force product is often used:
193 
194 \f$\begin{align*}\nu \times (Y \nu) &= \nu \times \BIN mv - mc\times \omega \\ mc\times v + I \omega - mc\times(c\times \omega) \BOUT \\&= \BIN m \omega\times v - \omega\times(mc\times \omega) \\ \omega \times ( mc \times v) + \omega \times (I\omega) -\omega \times(c \times( mc\times \omega)) -v\times(mc \times \omega)\BOUT\end{align*}\f$
195 
196 Setting \f$\beta=mc \times \omega\f$, this product can be written:
197 
198 \f$\nu \times (Y \nu) = \BIN \omega \times (m v - \beta) \\ \omega \times( c \times (mv-\beta)+I\omega) - v \times \beta \BOUT\f$
199 
200 This last form cost five \f$\times\f$, four \f$+\f$ and one \f$3\times3\f$ matrix-vector multiplication.
201 
202 ## Joint
203 
204 We denote by \f$1\f$ the coordinate system attached to the parent (predecessor) body at the joint input, ad by \f$2\f$
205 the coordinate system attached to the (child) successor body at the joint output. We neglect the possible time
206 variation of the joint model (ie the bias velocity \f$\sigma = \nu(q,0)\f$ is null).
207 
208 The joint geometry is expressed by the rigid transformation from the input to the ouput, parametrized by the joint
209 coordinate system \f$q \in \mathcal{Q}\f$:
210 
211 \f$ ^2m_1 \repr \ ^2M_1(q)\f$
212 
213 The joint velocity (i.e. the velocity of the child wrt. the parent in the child coordinate system) is:
214 
215 \f$^2\nu_{12} = \nu_J(q,v_q) = \ ^2S(q) v_q \f$
216 
217 where \f$^2S\f$ is the joint Jacobian (or constraint matrix) that define the motion subspace allowed by the joint, and
218 \f$v_q\f$ is the joint coordinate velocity (i.e. an element of the Lie algebra associated with the joint coordinate
219 manifold), which would be \f$v_q=\dot q\f$ when \f$\dot q\f$ exists.
220 
221 The joint acceleration is:
222 
223 \f$^2\alpha_{12} = S \dot v_q + c_J + \ ^2\nu_{1} \times \ ^2\nu_{12}\f$
224 
225 where \f$c_J = \sum_{i=1}^{n_q} \dpartial{S}{q_i} \dot q_i\f$ (null in the usual cases) and \f$^2\nu_{1}\f$ is the
226 velocity of the parent body with respect to an absolute (Galilean) coordinate system
227 
228 NB: The abosulte velocity
229 \f$\nu_{1}\f$ is also the relative velocity wrt. the Galilean coordinate system \f$\Omega\f$. The exhaustive notation
230 should be \f$\nu_{\Omega1}\f$ but \f$\nu_1\f$ is prefered for simplicity.
231 
232 The joint calculations take as input the joint position \f$q\f$ and velocity \f$v_q\f$ and should output \f$^2M_1\f$,
233 \f$^2\nu_{12}\f$ and \f$^2c\f$ (this last vector being often a trivial \f$0_6\f$ vector). In addition, the joint model
234 should store the position of the joint input in the central coordinate system of the previous joint \f$^0m_1\f$ which is a constant value.
235 
236 The joint integrator computes the exponential map associated with the joint manifold. The function inputs are the
237 initial position \f$q_0\f$, the velocity \f$v_q\f$ and the length of the integration interval \f$t\f$. It computes \f$q_t\f$ as:
238 
239 \f$ q_t = q_0 + \int_0^t v_q dt\f$
240 
241 For the simple vectorial case where \f$v_q=\dot q\f$, we have \f$q_t=q_0 + t v_q\f$. Written in the more general case of a Lie groupe, we have \f$q_t = q_0 exp(t v_q)\f$ where \f$exp\f$ denotes the exponential map (i.e. integration of a constant vector field from the Lie algebra into the Lie group). This integration only consider first order explicit Euler. More general integrators (e.g. Runge-Kutta in Lie groupes) remains to be written. Adequate references are welcome.
242 
243 ## RNEA
244 
245 ### Initialization
246 \f$^0\nu_0 = 0 ; \ ^0\alpha_0 = -g\f$
247 
248 In the following, the coordinate system \f$i\f$ is attached to the output of the joint (child body), while \f$lambda(i)\f$ is the central coordinate system attached to the parent joint. The coordinated system associated with the joint input is denoted by \f$i_0\f$. The constant rigid transformation from \f$\lambda(i)\f$ to the joint input is then \f$^{\lambda(i)}M_{i_0}\f$.
249 
250 
251 ### Forward loop
252 For each joint \f$i\f$, update the joint calculation \f$\mathbf j_i\f$.calc(\f$q,v_q\f$). This compute \f$\mathbf{j}.M = \ ^{\lambda(i)}M_{i_0}(q)\f$, \f$\mathbf{j}.\nu = \ ^i\nu_{{\lambda(i)}i}(q,v_q)\f$, \f$\mathbf{j}.S = \ ^iS(q)\f$ and \f$\mathbf{j}.c = \sum_{k=1}^{n_q} \dpartial{^iS}{q_k} \dot q_k\f$. Attached to the joint is also its placement in body \f$\lambda(i)\f$ denoted by \f$\mathbf{j}.M_0 =\ ^{\lambda(i)}M_{i_0}\f$. Then:
253 
254 \f$^{\lambda(i)}M_i = \mathbf{j}.M_0 \ \mathbf{j}.M \f$
255 
256 \f$^0M_i = \ ^0M_{\lambda(i)} \ ^{\lambda(i)}M_i\f$
257 
258 \f$^i\nu_{i}= \ ^{\lambda(i)}X_i^{-1} \ ^{\lambda(i)}\nu_{{\lambda(i)}} + \mathbf{j}.\nu\f$
259 
260 \f$^i\alpha_{i}= \ ^{\lambda(i)}X_i^{-1} \ ^{\lambda(i)}\alpha_{{\lambda(i)}} + \mathbf{j}.S \dot v_q + \mathbf{j}.c + \ ^i\nu_{i} \times \mathbf{j}.\nu\f$
261 
262 \f$^i\phi_i= \ ^iY_i \ ^i\alpha_i + \ ^i\nu_i \times \ ^iY_i \ ^i\nu_i - \ ^0X_i^{-*}\ ^0\phi_i^{ext}\f$
263 
264 ### Backward loop
265 For each joint \f$i\f$ from leaf to root, do:
266 
267 \f$\tau_i = \mathbf{j}.S^T \ ^i\phi_i\f$
268 
269 \f$^{\lambda(i)}\phi_{\lambda(i)} \ +\!\!= \ ^{\lambda(i)}X_i^{*} \ ^i\phi_i\f$
270 
271 ### Nota
272 It is more efficient to apply \f$X^{-1}\f$ than \f$X\f$. Similarly, it is more efficient to apply \f$X^{-*}\f$ than \f$X^*\f$. Therefore, it is better to store the transformations \f$^{\lambda(i)}m_i\f$ and \f$^0m_i\f$ than \f$^im_{\lambda(i)}\f$ and \f$^im_0\f$.
273 
274 </div>