When designing Cartesian impedance controllers, one often wants to control w.r.t what reference frame the Cartesian impedance is applied. For example, the world frame, workpiece frame, or the robot TCP frame. Since the magnitude of impedance is defined by the corresponding stiffness and damping matrices. So the question becomes how to change the reference frame (or mathematically, basis) of these matrices.
Changing reference frame of control gain matrices can be interpreted in one of the following ways.
1. From the force perspective, taking stiffness matrix \( K \in \mathbb{R}^{6 \times 6} \) for example, $$ F_t = K_t x_t $$ $$ \sideset{^t}{_b}{P} F_b = K_t (\sideset{^t}{_b}{P} x_b) $$ $$ F_b = (\sideset{^t}{_b^T}{P} K_t \sideset{^t}{_b}{P}) x_b $$ which leads to, $$ K_b = \sideset{^t}{_b^T}{P} K_t \sideset{^t}{_b}{P} = \sideset{^b}{_t}{P} K_t \sideset{^b}{_t^T}{P} $$ where \( P \in \mathbb{R}^{6\times6} \) is the plucker rotation, \( x \in \mathbb{R}^6 \) and \( F \in \mathbb{R}^6 \) are the displacement and wrench, super and subscript \( t \) and \( b \) stand for task and base frames, respectively.
2. From the kinetic energy perspective, $$ E = \frac{1}{2} x_t^T K_t x_t = \frac{1}{2} x_b^T K_b x_b $$ Substituting $$ x_t = \sideset{^t}{_b}{P} x_b $$ into the energy function, one gets the same results as from force perspective.
Damping can be considered as providing damping force \( \mathcal{F} \) through velocity \( V \) and the damping matrix \( D \), that is, $$ \mathcal{F}_t = D_t v_t $$ Following the same reasoning and notice, $$ \mathcal{F}_t = \sideset{^t}{_b}{P} \mathcal{F}_b $$ $$ v_t = \sideset{^t}{_b}{P} v_b $$ one gets the same conclusion $$ D_b = \sideset{^t}{_b^T}{P} D_t \sideset{^t}{_b}{P} = \sideset{^b}{_t}{P} D_t \sideset{^b}{_t^T}{P} $$ as in the case of stiffness matrix, and so forth for other impedance parameters.
Sometimes people want to know what's the Cartesian impedance when given certain joint space impedance, and vice versa. This can be analyzed using the energy method. $$ E = \frac{1}{2} \Delta q^T K_j \Delta q = \frac{1}{2} \Delta x^T K_c \Delta x $$ where \( K_j, K_c \) are joint and Cartesian space stiffness, \( \Delta q, \Delta x \) are joint and Cartesian space small displacement.
Note that for small displacement, $$ \Delta x = J \Delta q $$ substituting into the energy function, one gets, $$ E = \frac{1}{2} \Delta x^T K_c \Delta x = \frac{1}{2} \Delta q^T (J^T K_c J) \Delta q $$ and $$ E = \frac{1}{2} \Delta q^T K_j \Delta q = \frac{1}{2} \Delta x^T (\bar{J}^{T} K_j \bar{J}) \Delta x $$ Which indicates, $$ K_j = J^T K_c J $$ and $$ K_c = \bar{J}^{T} K_j \bar{J} $$ where \( \bar{J} \) is the generalized inverse of the Jacobian matrix, could be the dynamically consistent generalized inverse \( \bar{J} = M^{-1} J^T \Lambda \) as in Operational Space Framework, Hybrid Motion-Force Control, or a pseudo inverse \( \bar{J} = J^{\dagger} \).
To generalize, (1) when changing the reference frame of a quantity, a left multiplication of a transformation is enough; however, (2) when changing the reference frame of an operator (that maps one quantity to another quantity in the same frame), it requires a left multiplication of a transformation, and a right multiplication of the transformation inverse, because of the following relationship, $$ Y_a = \mathcal{O}_a x_a $$ $$ x_a = \sideset{^a}{_b}{T} x_b $$ $$ Y_a = \sideset{^a}{_b}{T} Y_b $$ $$ \sideset{^a}{_b}{T} Y_b = \mathcal{O}_a \cdot \sideset{^a}{_b}{T} x_b $$ $$ Y_b = \sideset{^a}{_b^{-1}}{T} \mathcal{O}_a \sideset{^a}{_b}{T} \cdot x_b $$ $$ Y_b = \mathcal{O}_b x_b $$ $$ \mathcal{O}_b = \sideset{^a}{_b^{-1}}{T} \mathcal{O}_a \sideset{^a}{_b}{T} $$ where \( x \) and \( Y \) are quantities in some space, \( \mathcal{O} \) is an operator that maps \( x \) to \( Y \), and \( T \) is an transformation of an quantity from one frame to another in the same space (assuming invertible), super and subscripts \( a \) and \( b \) denote two different frames of reference in the space.
The \( x \) and \( Y \) can be \( SE(3) \) poses, the operator can be a homogeneous transformation; or, the \( x \) and \( Y \) can be stiffness matrices, and the operator can be a stiffness change of reference frame. One can observe that in the linear cases, this is the exactly the same as matrix change of basis as in Wikipedia@ChangeOfBasis .