The most fundamental Cartesian motion control task requires a robot to move its end-effector from its current pose $T(R, p)$ to a desired pose $T_d(R_d, p_d)$ in the 6-dimensional Cartesian space. There are typically two ways to achieve that.
One way is to have the robot moving directly from $T$ to $T_d$ along the screw axis. With this method, the robot motion trajectory is a straight line along the screw axis, but not so in the Cartesian space.
The other way is to divide the motion into rotation and translation, and have the robot moving its orientation from $R$ to $R_d$, position from $p$ to $p_d$ separately and simultaneously. With this method, the robot motion trajectory is a straight line in the Cartesian space. As a result, the rotation-translation method is oftentimes the preferred the method for Cartesian robot control tasks.
The position difference $p_{\Delta} \in \mathbb{R}^3$ can be represented by a straightforward equation $$p_{\Delta} = p_d - p$$ since $p, p_d$ are both values in $\mathbb{R}^3$, and the physical meaning of the equation is rather obvious. However, the orientation difference $\theta_{\Delta} \in \mathbb{R}^3$ is typically written as $$\theta_{\Delta} = \Big[ \text{log}(R_d R^T) \Big]_{\vee} \label{eq:log-r}$$ or $$\theta_{\Delta} = 2\Big[ \text{log}(q_d q^*) \Big]_{\mathcal{Q}^{-1}} \label{eq:log-q}$$ where $q, q_d \in \mathbb{H}_1$ represent the same orientations as $R, R_d \in SO(3)$, respectively, are not so easy to understand and physically interpret.
This post discusses the physical meaning and derivation of orientation difference equations in \eqref{eq:log-r} and \eqref{eq:log-q}, and their variations and applications in robot Cartesian motion control tasks. For further reading, please refer to 2017@Lynch , 2020@Huber , Wikipedia@QuatAndRot , and 1998@Dam .
In addition to formulas and notations used in Exponential and Logarithm in SO(3), SE(3), Quaternion Space and Spatial Kinematics and Transformations, the following notations are employed in this post.
Given a 3-dimensional vector $\omega \in \mathbb{R}^3$, we define $$\Big[ [\omega]_{\times} \Big]_{\vee} \triangleq \omega \label{eq:ss-to-vec}$$ where $[\omega]_{\times}$ is the skew-symmetric matrix of $\omega$.
Given a pure quaternion $\mathcal{Q} = \begin{bmatrix} 0 & \frac{\theta}{2}\hat{\omega} \end{bmatrix} \in \mathbb{H} \label{eq:quat-to-vec}$, we define $$\Big[ \mathcal{Q} \Big]_{\mathcal{Q}^{-1}} \triangleq \frac{\theta}{2}\hat{\omega} $$ where $\theta \in \mathbb{R}$ and $\hat{\omega} \in \mathbb{R}^3$ with $||\hat{\omega}||=1$ are the half rotation angle and the unit rotation axis that $\mathcal{Q}$ represents.
For a general quaternion $q = \begin{bmatrix} q_0 & q_1 & q_2 & q_3 \end{bmatrix} \in \mathbb{H}$, its conjugate $q^*$ is defined to be $$q^* \triangleq \begin{bmatrix} q_0 & -q_1 & -q_2 & -q_3 \end{bmatrix} $$
For a general quaternion $q = \begin{bmatrix} q_0 & q_1 & q_2 & q_3 \end{bmatrix} \in \mathring{\mathbb{H}}$, its inverse $q^{-1}$ is defined to be $$q^{-1} \triangleq \frac{q^*}{||q||^2} $$ where $\mathring{\mathbb{H}} \triangleq \mathbb{H} \, \backslash \, \{0,0,0,0\}$.
For a unit quaternion $q \in \mathbb{H}_1$ with $||q|| = 1$, one gets $$ q^{-1} = q^* $$ similar to $R^{-1} = R^T$.
For two quaternions $q, q' \in \mathbb{H}$, the multiplication is defined to be $$ q q' \triangleq (q_0 + \mathbf{i}q_1 + \mathbf{j}q_2 + \mathbf{k}q_3) (q'_0 + \mathbf{i}q'_1 + \mathbf{j}q'_2 + \mathbf{k}q'_3) $$ with $$\mathbf{i}^2 \triangleq \mathbf{j}^2 \triangleq \mathbf{k}^2 \triangleq \mathbf{i}\mathbf{j}\mathbf{k}$$ and $\mathbf{i}\mathbf{j} \triangleq \mathbf{k}, \mathbf{j}\mathbf{i} \triangleq -\mathbf{k}$. Based on these definitions, one gets $$qq^{-1} = qq^* = \begin{bmatrix} 1 & \mathbf{0} \end{bmatrix} \triangleq I_q $$ for $q\in \mathbb{H}^1$, similar to $RR^T = RR^{-1} = I$.
Given an initial orientation, if it is rotated with respect to the space frame to get a final orientation, and if initial orientation, rotation with respect to the space frame, and final orientation can be represented by either $q_i, q_s, q_f \in \mathbb{H}_1$ or $R_i, R_s, R_f \in SO(3)$, respectively, the quaternion formula $$ q_f = q_s q_i $$ represents the similar physics as the rotation matrix formula $$ R_f = R_s R_i $$
Similarly, if the rotation is with respect to the body frame and can be represented by either $q_b \in \mathbb{H}_1$ or $R_b \in SO(3)$, then, quaternion formula $$ q_f = q_i q_b $$ encodes the similar physics as the rotation matrix formula $$ R_f = R_i R_b $$
Whereas the only caveat is the "half-angle" correspondence between quaternions and rotation matrices.
In the context of Cartesian motion control tasks, one typically have access to robot Cartesian twist, directly or indirectly. Take a robot for example, via velocity kinematics, one has $$ \mathcal{V}_s = \begin{bmatrix} \omega \\ v \end{bmatrix} = J_s \dot{q} \label{eq:vel-kine-space} $$ where $\mathcal{V}_s \in \mathbb{R}^6$ is the end-effector twist expressed in the space frame, $\dot{q} \in \mathbb{R}^n$ is the robot joint velocity, $J_s \in \mathbb{R}^{6\times n}$ is the robot space Jacobian.
With the rotation-translation control method, Cartesian motion control tasks can be physically interpreted as follows:
For the translation, it's straightforward. So, let's take a further look at the rotation physics. We know that $$R_d = R_s R $$ where $R_s$ is the rotation w.r.t to the space frame that take from $R$ to $R_d$, and $$R_s(\frac{\theta_{\Delta}}{||\theta_{\Delta}||}, ||\theta_{\Delta}||) = R_d R^T$$ Furthermore, from Exponential and Logarithm in SO(3), SE(3), Quaternion Space, we know that $$ \text{log}(R_s) = \Big[ \frac{\theta_{\Delta}}{||\theta_{\Delta}||} \Big]_{\times} ||\theta_{\Delta}|| = \Big[ \theta_{\Delta} \Big]_{\times} \in so(3) $$ then, employing mathematical operator in \eqref{eq:ss-to-vec}, one gets $$ \Big[ \text{log}(R_s) \Big]_{\vee} = \frac{\theta_{\Delta}}{||\theta_{\Delta}||} ||\theta_{\Delta}|| \in \mathbb{R}^3 $$ Connecting to \eqref{eq:log-r}, one gets $$ \theta_{\Delta} = \Big[ \text{log}(R_s) \Big]_{\vee} = \Big[ \text{log}(\textcolor{blue}{R_d R^T}) \Big]_{\vee} = \frac{\theta_{\Delta}}{||\theta_{\Delta}||} ||\theta_{\Delta}|| \label{eq:log-r-omega-e} $$ The physical meaning then becomes very clear, and can be interpreted in either one of the following ways:
On a side note, the translation difference can be interpreted in the same ways:
For the same process described by quaternions, the interpretation is almost exactly the same as the interpretation in the rotation matrix version, with the only difference manifested by the "half-angle" correspondence. Mathematically, it can be summarized as follows.
$$q_d = q_s q$$ $$q_s(\hat{\omega}, \frac{\theta}{2}) = q_d q^{-1} = q_d q^*$$ $$\text{log}(q_s) = \begin{bmatrix} 0 & \frac{\theta}{2} \hat{\omega} \end{bmatrix} \in \mathbb{H} $$ $$ 2\Big[ \text{log}(q_s) \Big]_{\mathcal{Q}^{-1}} = 2\Big[ \text{log}(\textcolor{blue}{q_d q^*}) \Big]_{\mathcal{Q}^{-1}} = 2\frac{\theta}{2} \hat{\omega} = \hat{\omega} \theta \in \mathbb{R}^3 \label{eq:log-q-omega-e} $$ where, to reduce cluttering from the above equations $$\hat{\omega} = \frac{\theta_{\Delta}}{|| \theta_{\Delta} ||}$$ is the unit rotation axis, and $$\theta = ||\theta_{\Delta}||$$ is the rotation angle about the unit rotation axis. The physical interpretation of the above equations is exactly the same as in \eqref{eq:log-r-omega-e}, only the mathematical computation method for orientation difference is different.
Equation \eqref{eq:log-r-omega-e} and \eqref{eq:log-q-omega-e} represent a rotation with respect to the space frame. Sometime the rotation is with respect to the body frame, for example in Section 11.3.3 in 2017@Lynch .
In such cases, the body frame rotation $R_b$ or $q_b$ and orientation relationships are $$ R_d = R R_b $$ and $$ q_d = q q_b $$
By the same reasoning, it is not difficult to get $$ \theta_{\Delta} = \Big[ \text{log}(R_b) \Big]_{\vee} = \Big[ \text{log}(\textcolor{red}{R^T R_d}) \Big]_{\vee} = \hat{\omega} \theta $$ and $$ 2\Big[ \text{log}(q_b) \Big]_{\mathcal{Q}^{-1}} = 2\Big[ \text{log}(\textcolor{red}{q^* q_d} ) \Big]_{\mathcal{Q}^{-1}} = 2\frac{\theta}{2} \hat{\omega} = \hat{\omega} \theta \in \mathbb{R}^3 $$
This case corresponds to the robot kinematics governed by $$ \mathcal{V}_b = J_b \dot{q} \label{eq:vel-kine-body} $$ where $\mathcal{V}_s \in \mathbb{R}^6$ is the end-effector twist expressed in the body frame, $J_b \in \mathbb{R}^{6\times n}$ is the robot body Jacobian. And of course, to convert from $J_b$ to $J_s$ or vice versa, one can apply the corresponding Plucker rotations.
With the above discussion, one can derive a simple Cartesian motion control law, for example, in the context of \eqref{eq:vel-kine-space} with orientation difference computed via rotation matrices in \eqref{eq:log-r-omega-e} as $$\dot{q} = J_s^{\dagger} u$$ where $J_s^{\dagger}$ is some generalized inverse of the space Jacobian and $$u = \mathcal{V}_d + K_p X_e + K_i \int_0^t X_e dt $$ where $K_p, K_i \in \mathbb{R}^{6 \times 6}$ are positive-definite symmetric gain matrices, $$\mathcal{V}_d = \begin{bmatrix} \omega_d \\ v_d \end{bmatrix}$$ is the desired terminal twist expressed in the space frame, and $$X_e = \begin{bmatrix} \theta_e \\ p_e \end{bmatrix} = \begin{bmatrix} \Big[ \text{log}(R_d R^T) \Big]_{\vee} \\ p_d - p \end{bmatrix} \in \mathbb{R}^6$$ is the pose error expressed in the space frame with orientation and translation components.
Following the same logic, one can also derive control laws in the context of \eqref{eq:vel-kine-body} or based on robot dynamics, and with orientation difference computed via other methods. Note that here we use $\theta_e$ and $p_e$ to follow the control's convention, obviously, $\theta_e = \theta_{\Delta}$ and $p_e = p_{\Delta}$.
Sometimes people use an alternative control law given by $$u = \begin{bmatrix} R_d R^T & 0 \\ 0 & I \end{bmatrix} \mathcal{V}_d + K_p X_e + K_i \int_0^t X_e dt \label{eq:motion-control} $$ where the desired angular velocity feed-forward term $$ \omega_{ff} = R_d R^T \omega_d \label{eq:omega-ff} $$ requires a little more physical interpretation. To do that, let's rewrite \eqref{eq:omega-ff} with explicity reference frame notations, $$ \omega_{ff, \{s\}} = \sideset{^{\{s\}}}{}{R_{d,\{b\}}} \, \Big( \sideset{^{\{s\}}}{}{R_{\{b\}}} \Big)^T \, \omega_{d,\{s\}} = \sideset{^{\{s\}}}{}{R_{d,\{b\}}} \, \sideset{^{\{b\}}}{}{R_{\{s\}}} \, \omega_{d,\{s\}} \label{eq:omega-ff-expansion} $$ where $\{s\}$ denotes the space (robot base) frame, $\{b\}$ denotes the body (end-effector) frame. With \eqref{eq:omega-ff-expansion}, the physical meaning of the desired angular velocity feed-forward term becomes clear, i.e., it is the desired angular velocity expressed in the space frame rotated to the instantaneous body end-effector frame (assuming having desired orientation), then rotated back to the space (robot base) frame.
There are other ways to compute orientation difference, such as in 2005@Khatib , for the mapping they chose to represent the rotation might be different and used less often. Yet the interpretation presented in this post should be sufficient for analyzing and deriving various representations of the same physics.
For $SO(3)$ and quaternion logarithm, please refer to Exponential and Logarithm in SO(3), SE(3), Quaternion Space and be aware of the corner cases and numerical stability notes.