liegroups¶
The default implementation uses numpy as the backend linear algebra library.
SO(2)¶
-
liegroups.
SO2
¶ alias of
liegroups.numpy.so2.SO2Matrix
-
class
liegroups.numpy.so2.
SO2Matrix
(mat)¶ Rotation matrix in \(SO(2)\) using active (alibi) transformations.
\[\begin{split}SO(2) &= \left\{ \mathbf{C} \in \mathbb{R}^{2 \times 2} ~\middle|~ \mathbf{C}\mathbf{C}^T = \mathbf{1}, \det \mathbf{C} = 1 \right\} \\ \mathfrak{so}(2) &= \left\{ \boldsymbol{\Phi} = \phi^\wedge \in \mathbb{R}^{2 \times 2} ~\middle|~ \phi \in \mathbb{R} \right\}\end{split}\]- Variables
dim – Dimension of the rotation matrix.
dof – Underlying degrees of freedom (i.e., dimension of the tangent space).
mat – Storage for the rotation matrix \(\mathbf{C}\).
-
adjoint
()¶ Adjoint matrix of the transformation.
\[\text{Ad}(\mathbf{C}) = 1\]
-
as_matrix
()¶ Return the matrix representation of the rotation.
-
dim
= 2¶ Dimension of the transformation matrix.
-
dof
= 1¶ Underlying degrees of freedom (i.e., dimension of the tangent space).
-
dot
(other)¶ Multiply another rotation or one or more vectors on the left.
-
classmethod
exp
(phi)¶ Exponential map for \(SO(2)\), which computes a transformation from a tangent vector:
\[\begin{split}\mathbf{C}(\phi) = \exp(\phi^\wedge) = \cos \phi \mathbf{1} + \sin \phi 1^\wedge = \begin{bmatrix} \cos \phi & -\sin \phi \\ \sin \phi & \cos \phi \end{bmatrix}\end{split}\]This is the inverse operation to
log()
.
-
classmethod
from_angle
(angle_in_radians)¶ Form a rotation matrix given an angle in radians.
See
exp()
-
classmethod
from_matrix
(mat, normalize=False)¶ Create a rotation from a matrix (safe, but slower).
Throws an error if mat is invalid and normalize=False. If normalize=True invalid matrices will be normalized to be valid.
-
classmethod
identity
()¶ Return the identity rotation.
-
inv
()¶ Return the inverse rotation:
\[\mathbf{C}^{-1} = \mathbf{C}^T\]
-
classmethod
inv_left_jacobian
(phi)¶ \(SO(2)\) inverse left Jacobian.
\[\begin{split}\mathbf{J}^{-1}(\phi) = \begin{cases} \mathbf{1} - \frac{1}{2} \phi^\wedge, & \text{if } \phi \text{ is small} \\ \frac{\phi}{2} \cot \frac{\phi}{2} \mathbf{1} - \frac{\phi}{2} 1^\wedge, & \text{otherwise} \end{cases}\end{split}\]
-
classmethod
is_valid_matrix
(mat)¶ Check if a matrix is a valid rotation matrix.
-
classmethod
left_jacobian
(phi)¶ \(SO(2)\) left Jacobian.
\[\begin{split}\mathbf{J}(\phi) = \begin{cases} \mathbf{1} + \frac{1}{2} \phi^\wedge, & \text{if } \phi \text{ is small} \\ \frac{\sin \phi}{\phi} \mathbf{1} - \frac{1 - \cos \phi}{\phi} 1^\wedge, & \text{otherwise} \end{cases}\end{split}\]
-
log
()¶ Logarithmic map for \(SO(2)\), which computes a tangent vector from a transformation:
\[\phi(\mathbf{C}) = \ln(\mathbf{C})^\vee = \text{atan2}(C_{1,0}, C_{0,0})\]This is the inverse operation to
exp()
.
-
normalize
()¶ Normalize the rotation matrix to ensure it is valid and negate the effect of rounding errors.
-
perturb
(phi)¶ Perturb the rotation in-place on the left by a vector in its local tangent space.
\[\mathbf{C} \gets \exp(\boldsymbol{\phi}^\wedge) \mathbf{C}\]
-
to_angle
()¶ Recover the rotation angle in radians from the rotation matrix.
See
log()
-
classmethod
vee
(Phi)¶ \(SO(2)\) vee operator as defined by Barfoot.
\[\phi = \boldsymbol{\Phi}^\vee\]This is the inverse operation to
wedge()
.
-
classmethod
wedge
(phi)¶ \(SO(2)\) wedge operator as defined by Barfoot.
\[\begin{split}\boldsymbol{\Phi} = \phi^\wedge = \begin{bmatrix} 0 & -\phi \\ \phi & 0 \end{bmatrix}\end{split}\]This is the inverse operation to
vee()
.
SE(2)¶
-
liegroups.
SE2
¶ alias of
liegroups.numpy.se2.SE2Matrix
-
class
liegroups.numpy.se2.
SE2Matrix
(rot, trans)¶ Homogeneous transformation matrix in \(SE(2)\) using active (alibi) transformations.
\[\begin{split}SE(2) &= \left\{ \mathbf{T}= \begin{bmatrix} \mathbf{C} & \mathbf{r} \\ \mathbf{0}^T & 1 \end{bmatrix} \in \mathbb{R}^{3 \times 3} ~\middle|~ \mathbf{C} \in SO(2), \mathbf{r} \in \mathbb{R}^2 \right\} \\ \mathfrak{se}(2) &= \left\{ \boldsymbol{\Xi} = \boldsymbol{\xi}^\wedge \in \mathbb{R}^{3 \times 3} ~\middle|~ \boldsymbol{\xi}= \begin{bmatrix} \boldsymbol{\rho} \\ \phi \end{bmatrix} \in \mathbb{R}^3, \boldsymbol{\rho} \in \mathbb{R}^2, \phi \in \mathbb{R} \right\}\end{split}\]- Variables
dim – Dimension of the rotation matrix.
dof – Underlying degrees of freedom (i.e., dimension of the tangent space).
rot – Storage for the rotation matrix \(\mathbf{C}\).
trans – Storage for the translation vector \(\mathbf{r}\).
-
RotationType
¶ alias of
liegroups.numpy.so2.SO2Matrix
-
adjoint
()¶ Adjoint matrix of the transformation.
\[\begin{split}\text{Ad}(\mathbf{T}) = \begin{bmatrix} \mathbf{C} & 1^\wedge \mathbf{r} \\ \mathbf{0}^T & 1 \end{bmatrix} \in \mathbb{R}^{3 \times 3}\end{split}\]
-
as_matrix
()¶ Return the matrix representation of the rotation.
-
dim
= 3¶ Dimension of the transformation matrix.
-
dof
= 3¶ Underlying degrees of freedom (i.e., dimension of the tangent space).
-
dot
(other)¶ Multiply another rotation or one or more vectors on the left.
-
classmethod
exp
(xi)¶ Exponential map for \(SE(2)\), which computes a transformation from a tangent vector:
\[\begin{split}\mathbf{T}(\boldsymbol{\xi}) = \exp(\boldsymbol{\xi}^\wedge) = \begin{bmatrix} \exp(\phi ^\wedge) & \mathbf{J} \boldsymbol{\rho} \\ \mathbf{0} ^ T & 1 \end{bmatrix}\end{split}\]This is the inverse operation to
log()
.
-
classmethod
from_matrix
(mat, normalize=False)¶ Create a transformation from a matrix (safe, but slower).
Throws an error if mat is invalid and normalize=False. If normalize=True invalid matrices will be normalized to be valid.
-
classmethod
identity
()¶ Return the identity transformation.
-
inv
()¶ Return the inverse transformation:
\[\begin{split}\mathbf{T}^{-1} = \begin{bmatrix} \mathbf{C}^T & -\mathbf{C}^T\mathbf{r} \\ \mathbf{0}^T & 1 \end{bmatrix}\end{split}\]
-
classmethod
inv_left_jacobian
(xi)¶ \(SE(2)\) inverse left Jacobian.
\[\mathcal{J}^{-1}(\boldsymbol{\xi})\]
-
classmethod
is_valid_matrix
(mat)¶ Check if a matrix is a valid transformation matrix.
-
classmethod
left_jacobian
(xi)¶ \(SE(2)\) left Jacobian.
\[\mathcal{J}(\boldsymbol{\xi})\]
-
log
()¶ Logarithmic map for \(SE(2)\), which computes a tangent vector from a transformation:
\[\begin{split}\boldsymbol{\xi}(\mathbf{T}) = \ln(\mathbf{T})^\vee = \begin{bmatrix} \mathbf{J} ^ {-1} \mathbf{r} \\ \ln(\boldsymbol{C}) ^\vee \end{bmatrix}\end{split}\]This is the inverse operation to
log()
.
-
normalize
()¶ Normalize the transformation matrix to ensure it is valid and negate the effect of rounding errors.
-
classmethod
odot
(p, directional=False)¶ \(SE(2)\) odot operator as defined by Barfoot.
This is the Jacobian of a vector
\[\begin{split}\mathbf{p} = \begin{bmatrix} sx \\ sy \\ sz \\ s \end{bmatrix} = \begin{bmatrix} \boldsymbol{\epsilon} \\ \eta \end{bmatrix}\end{split}\]with respect to a perturbation in the underlying parameters of \(\mathbf{T}\).
If \(\mathbf{p}\) is given in Euclidean coordinates and directional=False, the missing scale value \(\eta\) is assumed to be 1 and the Jacobian is 2x3. If directional=True, \(\eta\) is assumed to be 0:
\[\mathbf{p}^\odot = \begin{bmatrix} \eta \mathbf{1} & 1^\wedge \boldsymbol{\epsilon} \end{bmatrix}\]If \(\mathbf{p}\) is given in Homogeneous coordinates, the Jacobian is 3x3:
\[\begin{split}\mathbf{p}^\odot = \begin{bmatrix} \eta \mathbf{1} & 1^\wedge \boldsymbol{\epsilon} \\ \mathbf{0}^T & 0 \end{bmatrix}\end{split}\]
-
perturb
(xi)¶ Perturb the transformation in-place on the left by a vector in its local tangent space.
\[\mathbf{T} \gets \exp(\boldsymbol{\xi}^\wedge) \mathbf{T}\]
-
classmethod
vee
(Xi)¶ \(SE(2)\) vee operator as defined by Barfoot.
\[\boldsymbol{\xi} = \boldsymbol{\Xi} ^\vee\]This is the inverse operation to
wedge()
.
-
classmethod
wedge
(xi)¶ \(SE(2)\) wedge operator as defined by Barfoot.
\[\begin{split}\boldsymbol{\Xi} = \boldsymbol{\xi} ^\wedge = \begin{bmatrix} \phi ^\wedge & \boldsymbol{\rho} \\ \mathbf{0} ^ T & 0 \end{bmatrix}\end{split}\]This is the inverse operation to
vee()
.
SO(3)¶
-
liegroups.
SO3
¶ alias of
liegroups.numpy.so3.SO3Matrix
-
class
liegroups.numpy.so3.
SO3Matrix
(mat)¶ Rotation matrix in \(SO(3)\) using active (alibi) transformations.
\[\begin{split}SO(3) &= \left\{ \mathbf{C} \in \mathbb{R}^{3 \times 3} ~\middle|~ \mathbf{C}\mathbf{C}^T = \mathbf{1}, \det \mathbf{C} = 1 \right\} \\ \mathfrak{so}(3) &= \left\{ \boldsymbol{\Phi} = \boldsymbol{\phi}^\wedge \in \mathbb{R}^{3 \times 3} ~\middle|~ \boldsymbol{\phi} = \phi \mathbf{a} \in \mathbb{R}^3, \phi = \Vert \boldsymbol{\phi} \Vert \right\}\end{split}\]- Variables
dim – Dimension of the rotation matrix.
dof – Underlying degrees of freedom (i.e., dimension of the tangent space).
mat – Storage for the rotation matrix \(\mathbf{C}\).
-
adjoint
()¶ Adjoint matrix of the transformation.
\[\text{Ad}(\mathbf{C}) = \mathbf{C} \in \mathbb{R}^{3 \times 3}\]
-
as_matrix
()¶ Return the matrix representation of the rotation.
-
dim
= 3¶ Dimension of the transformation matrix.
-
dof
= 3¶ Underlying degrees of freedom (i.e., dimension of the tangent space).
-
dot
(other)¶ Multiply another rotation or one or more vectors on the left.
-
classmethod
exp
(phi)¶ Exponential map for \(SO(3)\), which computes a transformation from a tangent vector:
\[\begin{split}\mathbf{C}(\boldsymbol{\phi}) = \exp(\boldsymbol{\phi}^\wedge) = \begin{cases} \mathbf{1} + \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ \cos \phi \mathbf{1} + (1 - \cos \phi) \mathbf{a}\mathbf{a}^T + \sin \phi \mathbf{a}^\wedge, & \text{otherwise} \end{cases}\end{split}\]This is the inverse operation to
log()
.
-
classmethod
from_matrix
(mat, normalize=False)¶ Create a rotation from a matrix (safe, but slower).
Throws an error if mat is invalid and normalize=False. If normalize=True invalid matrices will be normalized to be valid.
-
classmethod
from_quaternion
(quat, ordering='wxyz')¶ Form a rotation matrix from a unit length quaternion.
Valid orderings are ‘xyzw’ and ‘wxyz’.
\[\begin{split}\mathbf{C} = \begin{bmatrix} 1 - 2 (y^2 + z^2) & 2 (xy - wz) & 2 (wy + xz) \\ 2 (wz + xy) & 1 - 2 (x^2 + z^2) & 2 (yz - wx) \\ 2 (xz - wy) & 2 (wx + yz) & 1 - 2 (x^2 + y^2) \end{bmatrix}\end{split}\]
-
classmethod
from_rpy
(roll, pitch, yaw)¶ Form a rotation matrix from RPY Euler angles \((\alpha, \beta, \gamma)\).
\[\mathbf{C} = \mathbf{C}_z(\gamma) \mathbf{C}_y(\beta) \mathbf{C}_x(\alpha)\]
-
classmethod
identity
()¶ Return the identity rotation.
-
inv
()¶ Return the inverse rotation:
\[\mathbf{C}^{-1} = \mathbf{C}^T\]
-
classmethod
inv_left_jacobian
(phi)¶ \(SO(3)\) inverse left Jacobian.
\[\begin{split}\mathbf{J}^{-1}(\boldsymbol{\phi}) = \begin{cases} \mathbf{1} - \frac{1}{2} \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ \frac{\phi}{2} \cot \frac{\phi}{2} \mathbf{1} + \left( 1 - \frac{\phi}{2} \cot \frac{\phi}{2} \right) \mathbf{a}\mathbf{a}^T - \frac{\phi}{2} \mathbf{a}^\wedge, & \text{otherwise} \end{cases}\end{split}\]
-
classmethod
is_valid_matrix
(mat)¶ Check if a matrix is a valid rotation matrix.
-
classmethod
left_jacobian
(phi)¶ \(SO(3)\) left Jacobian.
\[\begin{split}\mathbf{J}(\boldsymbol{\phi}) = \begin{cases} \mathbf{1} + \frac{1}{2} \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ \frac{\sin \phi}{\phi} \mathbf{1} + \left(1 - \frac{\sin \phi}{\phi} \right) \mathbf{a}\mathbf{a}^T + \frac{1 - \cos \phi}{\phi} \mathbf{a}^\wedge, & \text{otherwise} \end{cases}\end{split}\]
-
log
()¶ Logarithmic map for \(SO(3)\), which computes a tangent vector from a transformation:
\[\begin{split}\phi &= \frac{1}{2} \left( \mathrm{Tr}(\mathbf{C}) - 1 \right) \\ \boldsymbol{\phi}(\mathbf{C}) &= \ln(\mathbf{C})^\vee = \begin{cases} \mathbf{1} - \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ \left( \frac{1}{2} \frac{\phi}{\sin \phi} \left( \mathbf{C} - \mathbf{C}^T \right) \right)^\vee, & \text{otherwise} \end{cases}\end{split}\]This is the inverse operation to
log()
.
-
normalize
()¶ Normalize the rotation matrix to ensure it is valid and negate the effect of rounding errors.
-
perturb
(phi)¶ Perturb the rotation in-place on the left by a vector in its local tangent space.
\[\mathbf{C} \gets \exp(\boldsymbol{\phi}^\wedge) \mathbf{C}\]
-
classmethod
rotx
(angle_in_radians)¶ Form a rotation matrix given an angle in rad about the x-axis.
\[\begin{split}\mathbf{C}_x(\phi) = \begin{bmatrix} 1 & 0 & 0 \\ 0 & \cos \phi & -\sin \phi \\ 0 & \sin \phi & \cos \phi \end{bmatrix}\end{split}\]
-
classmethod
roty
(angle_in_radians)¶ Form a rotation matrix given an angle in rad about the y-axis.
\[\begin{split}\mathbf{C}_y(\phi) = \begin{bmatrix} \cos \phi & 0 & \sin \phi \\ 0 & 1 & 0 \\ \sin \phi & 0 & \cos \phi \end{bmatrix}\end{split}\]
-
classmethod
rotz
(angle_in_radians)¶ Form a rotation matrix given an angle in rad about the z-axis.
\[\begin{split}\mathbf{C}_z(\phi) = \begin{bmatrix} \cos \phi & -\sin \phi & 0 \\ \sin \phi & \cos \phi & 0 \\ 0 & 0 & 1 \end{bmatrix}\end{split}\]
-
to_quaternion
(ordering='wxyz')¶ Convert a rotation matrix to a unit length quaternion.
Valid orderings are ‘xyzw’ and ‘wxyz’.
-
to_rpy
()¶ Convert a rotation matrix to RPY Euler angles \((\alpha, \beta, \gamma)\).
-
classmethod
vee
(Phi)¶ \(SO(3)\) vee operator as defined by Barfoot.
\[\phi = \boldsymbol{\Phi}^\vee\]This is the inverse operation to
wedge()
.
-
classmethod
wedge
(phi)¶ \(SO(3)\) wedge operator as defined by Barfoot.
\[\begin{split}\boldsymbol{\Phi} = \boldsymbol{\phi}^\wedge = \begin{bmatrix} 0 & -\phi_3 & \phi_2 \\ \phi_3 & 0 & -\phi_1 \\ -\phi_2 & \phi_1 & 0 \end{bmatrix}\end{split}\]This is the inverse operation to
vee()
.
SE(3)¶
-
liegroups.
SE3
¶ alias of
liegroups.numpy.se3.SE3Matrix
-
class
liegroups.numpy.se3.
SE3Matrix
(rot, trans)¶ Homogeneous transformation matrix in \(SE(3)\) using active (alibi) transformations.
\[\begin{split}SE(3) &= \left\{ \mathbf{T}= \begin{bmatrix} \mathbf{C} & \mathbf{r} \\ \mathbf{0}^T & 1 \end{bmatrix} \in \mathbb{R}^{4 \times 4} ~\middle|~ \mathbf{C} \in SO(3), \mathbf{r} \in \mathbb{R}^3 \right\} \\ \mathfrak{se}(3) &= \left\{ \boldsymbol{\Xi} = \boldsymbol{\xi}^\wedge \in \mathbb{R}^{4 \times 4} ~\middle|~ \boldsymbol{\xi}= \begin{bmatrix} \boldsymbol{\rho} \\ \boldsymbol{\phi} \end{bmatrix} \in \mathbb{R}^6, \boldsymbol{\rho} \in \mathbb{R}^3, \boldsymbol{\phi} \in \mathbb{R}^3 \right\}\end{split}\]- Variables
dim – Dimension of the rotation matrix.
dof – Underlying degrees of freedom (i.e., dimension of the tangent space).
rot – Storage for the rotation matrix \(\mathbf{C}\).
trans – Storage for the translation vector \(\mathbf{r}\).
-
RotationType
¶ alias of
liegroups.numpy.so3.SO3Matrix
-
adjoint
()¶ Adjoint matrix of the transformation.
\[\begin{split}\text{Ad}(\mathbf{T}) = \begin{bmatrix} \mathbf{C} & \mathbf{r}^\wedge\mathbf{C} \\ \mathbf{0} & \mathbf{C} \end{bmatrix} \in \mathbb{R}^{6 \times 6}\end{split}\]
-
as_matrix
()¶ Return the matrix representation of the rotation.
-
classmethod
curlyvee
(Psi)¶ \(SE(3)\) curlyvee operator as defined by Barfoot.
\[\boldsymbol{\xi} = \boldsymbol{\Psi}^\curlyvee\]This is the inverse operation to
curlywedge()
.
-
classmethod
curlywedge
(xi)¶ \(SE(3)\) curlywedge operator as defined by Barfoot.
\[\begin{split}\boldsymbol{\Psi} = \boldsymbol{\xi}^\curlywedge = \begin{bmatrix} \boldsymbol{\phi}^\wedge & \boldsymbol{\rho}^\wedge \\ \mathbf{0} & \boldsymbol{\phi}^\wedge \end{bmatrix}\end{split}\]This is the inverse operation to
curlyvee()
.
-
dim
= 4¶ Dimension of the transformation matrix.
-
dof
= 6¶ Underlying degrees of freedom (i.e., dimension of the tangent space).
-
dot
(other)¶ Multiply another rotation or one or more vectors on the left.
-
classmethod
exp
(xi)¶ Exponential map for \(SE(3)\), which computes a transformation from a tangent vector:
\[\begin{split}\mathbf{T}(\boldsymbol{\xi}) = \exp(\boldsymbol{\xi}^\wedge) = \begin{bmatrix} \exp(\boldsymbol{\phi}^\wedge) & \mathbf{J} \boldsymbol{\rho} \\ \mathbf{0} ^ T & 1 \end{bmatrix}\end{split}\]This is the inverse operation to
log()
.
-
classmethod
from_matrix
(mat, normalize=False)¶ Create a transformation from a matrix (safe, but slower).
Throws an error if mat is invalid and normalize=False. If normalize=True invalid matrices will be normalized to be valid.
-
classmethod
identity
()¶ Return the identity transformation.
-
inv
()¶ Return the inverse transformation:
\[\begin{split}\mathbf{T}^{-1} = \begin{bmatrix} \mathbf{C}^T & -\mathbf{C}^T\mathbf{r} \\ \mathbf{0}^T & 1 \end{bmatrix}\end{split}\]
-
classmethod
inv_left_jacobian
(xi)¶ \(SE(3)\) inverse left Jacobian.
\[\begin{split}\mathcal{J}^{-1}(\boldsymbol{\xi}) = \begin{bmatrix} \mathbf{J}^{-1} & -\mathbf{J}^{-1} \mathbf{Q} \mathbf{J}^{-1} \\ \mathbf{0} & \mathbf{J}^{-1} \end{bmatrix}\end{split}\]with \(\mathbf{J}^{-1}\) as in
liegroups.SO3.inv_left_jacobian()
and \(\mathbf{Q}\) as inleft_jacobian_Q_matrix()
.
-
classmethod
is_valid_matrix
(mat)¶ Check if a matrix is a valid transformation matrix.
-
classmethod
left_jacobian
(xi)¶ \(SE(3)\) left Jacobian.
\[\begin{split}\mathcal{J}(\boldsymbol{\xi}) = \begin{bmatrix} \mathbf{J} & \mathbf{Q} \\ \mathbf{0} & \mathbf{J} \end{bmatrix}\end{split}\]with \(\mathbf{J}\) as in
liegroups.SO3.left_jacobian()
and \(\mathbf{Q}\) as inleft_jacobian_Q_matrix()
.
-
classmethod
left_jacobian_Q_matrix
(xi)¶ The \(\mathbf{Q}\) matrix used to compute \(\mathcal{J}\) in
left_jacobian()
and \(\mathcal{J}^{-1}\) ininv_left_jacobian()
.\[\begin{split}\mathbf{Q}(\boldsymbol{\xi}) = \frac{1}{2}\boldsymbol{\rho}^\wedge &+ \left( \frac{\phi - \sin \phi}{\phi^3} \right) \left( \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge + \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge + \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \right) \\ &+ \left( \frac{\phi^2 + 2 \cos \phi - 2}{2 \phi^4} \right) \left( \boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge + \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge - 3 \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \right) \\ &+ \left( \frac{2 \phi - 3 \sin \phi + \phi \cos \phi}{2 \phi^5} \right) \left( \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge + \boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \right)\end{split}\]
-
log
()¶ Logarithmic map for \(SE(3)\), which computes a tangent vector from a transformation:
\[\begin{split}\boldsymbol{\xi}(\mathbf{T}) = \ln(\mathbf{T})^\vee = \begin{bmatrix} \mathbf{J} ^ {-1} \mathbf{r} \\ \ln(\boldsymbol{C}) ^\vee \end{bmatrix}\end{split}\]This is the inverse operation to
exp()
.
-
normalize
()¶ Normalize the transformation matrix to ensure it is valid and negate the effect of rounding errors.
-
classmethod
odot
(p, directional=False)¶ \(SE(3)\) odot operator as defined by Barfoot.
This is the Jacobian of a vector
\[\begin{split}\mathbf{p} = \begin{bmatrix} sx \\ sy \\ sz \\ s \end{bmatrix} = \begin{bmatrix} \boldsymbol{\epsilon} \\ \eta \end{bmatrix}\end{split}\]with respect to a perturbation in the underlying parameters of \(\mathbf{T}\).
If \(\mathbf{p}\) is given in Euclidean coordinates and directional=False, the missing scale value \(\eta\) is assumed to be 1 and the Jacobian is 3x6. If directional=True, \(\eta\) is assumed to be 0:
\[\mathbf{p}^\odot = \begin{bmatrix} \eta \mathbf{1} & -\boldsymbol{\epsilon}^\wedge \end{bmatrix}\]If \(\mathbf{p}\) is given in Homogeneous coordinates, the Jacobian is 4x6:
\[\begin{split}\mathbf{p}^\odot = \begin{bmatrix} \eta \mathbf{1} & -\boldsymbol{\epsilon}^\wedge \\ \mathbf{0}^T & \mathbf{0}^T \end{bmatrix}\end{split}\]
-
perturb
(xi)¶ Perturb the transformation in-place on the left by a vector in its local tangent space.
\[\mathbf{T} \gets \exp(\boldsymbol{\xi}^\wedge) \mathbf{T}\]
-
classmethod
vee
(Xi)¶ \(SE(3)\) vee operator as defined by Barfoot.
\[\boldsymbol{\xi} = \boldsymbol{\Xi} ^\vee\]This is the inverse operation to
wedge()
.
-
classmethod
wedge
(xi)¶ \(SE(3)\) wedge operator as defined by Barfoot.
\[\begin{split}\boldsymbol{\Xi} = \boldsymbol{\xi} ^\wedge = \begin{bmatrix} \boldsymbol{\phi} ^\wedge & \boldsymbol{\rho} \\ \mathbf{0} ^ T & 0 \end{bmatrix}\end{split}\]This is the inverse operation to
vee()
.