3
$\begingroup$

Let us say we have a right-handed unit quaternion, describing the rotation from frame $a$ to frame $b$: $q_a^b$. The rotation matrix formed from this quaternion is $R\left( q_a^b \right)$ and describes a passive rotation. That is, $R\left( q_a^b \right)v$ describes the same object $v$ in the new frame $b$.

The following expression is given in Michael Andre Bloesh's dissertation without explanation link - (unfortunately embargoed until April 2018)

$$\frac{d}{dq_a^b} R\left( q_a^b \right)v = -\left( R\left( q_a^b \right)v \right)^\times $$

where the $\left( \cdot \right)^\times $ notation is the skew-symmetric matrix.

I played with these expressions numerically to confirm the above and also discovered that the derivative of the active rotation is

$$\frac{d}{dq_a^b} R\left( q_a^b \right)^\top v = \left( v \right)^\times R \left( q_a^b \right)^\top $$

which I guess makes some intuitive sense as well.

While these expressions seem to work, how do I approach this problem in a principled way (i.e. not guessing and checking with numerical differentiation)?

$\endgroup$
  • $\begingroup$ Did you manage to solve this in the end? $\endgroup$ – chutsu Mar 27 '18 at 17:30
2
$\begingroup$

I may have an answer, taking the derivation straight from "A Primer on the Differential Calculus of 3D Orientations" by Bloesch et al. (Appendix I: Section 3: Derivative of a Coordinate Map)

First, let $\Phi_{BA} \in SO(3)$ be a relative orientation of a coordinate system $B$ w.r.t. a coordinate system $A$. In the paper, they defined a mapping $\boldsymbol{C}: SO(3) \rightarrow \mathbb{R}^{3 \times 3}$ such that $\Phi(\mathbf{r}) \triangleq \boldsymbol{C}(\Phi) \mathbf{r}$ which means $\Phi$ can be a quaternion or euler angle (if I'm not mistaken). $\boldsymbol{e}_{i} \in \mathbb{R}^{3}$ be the standard basis vectors in $\mathbb{R}^{3}$, $\epsilon$ be a small scalar pertubation, and finally,

$$ \begin{align} \boxplus : SO(3) \times \mathbb{R}^{3} \rightarrow SO(3), \\ \Phi, \boldsymbol{\varphi} \mapsto \exp(\boldsymbol{\varphi}) \circ \Phi \end{align} $$

be the box-plus operator that forms the addition operator between $SO(3)$ and $\mathbb{R}^{3}$

Copying from the appendix to here, the map of an orientation applied to a coordinate tuple can be differentiated w.r.t. the orientation itself.

$$ \begin{align} \begin{bmatrix} \dfrac{\partial}{\partial \Phi} \Phi(\boldsymbol{r}) \end{bmatrix}_{i} &= \lim_{\epsilon \rightarrow 0} \dfrac{ (\Phi \boxplus \boldsymbol{e}_{i} \epsilon)(\boldsymbol{r}) - \Phi } { \epsilon } \\ &= \lim_{\epsilon \rightarrow 0} \dfrac{ \boldsymbol{C}(\boldsymbol{e}_{i} \epsilon) \boldsymbol{C}(\Phi)(\boldsymbol{r}) - \boldsymbol{C}(\Phi)(\boldsymbol{r}) } { \epsilon } \\ &= \lim_{\epsilon \rightarrow 0} \dfrac{ (\boldsymbol{I} + \boldsymbol{e}_{i}^{\times} \epsilon) \boldsymbol{C}(\Phi)(\boldsymbol{r}) - \boldsymbol{C}(\Phi)(\boldsymbol{r}) } { \epsilon } \\ &= \lim_{\epsilon \rightarrow 0} \dfrac{ \boldsymbol{e}_{i}^{\times} \epsilon \boldsymbol{C}(\Phi)(\boldsymbol{r}) } { \epsilon } \\ \dfrac{\partial}{\partial \Phi} \Phi(\boldsymbol{r}) &= -(\boldsymbol{C}(\Phi) \boldsymbol{r})^{\times} \end{align} $$

Highly encouraged to look at the paper to see the identities used for this derivation.

Please let me know if I got this wrong, I'm very new to differential geometry.

$\endgroup$
  • 1
    $\begingroup$ This is awesome! Thanks. That's definitely the way to get to the first one. I imagine you can get to the "active rotation" using a similar process. That's an awesome paper. Thanks for the link. $\endgroup$ – superjax Mar 28 '18 at 20:55

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service, privacy policy and cookie policy

Not the answer you're looking for? Browse other questions tagged or ask your own question.