Class inertialsim::geometry::RigidTransformBase¶
template <typename Derived>
ClassList > inertialsim > geometry > RigidTransformBase
CRTP base for 3-dimensional rigid body transform types. More...
#include <rigid_transform_base.h>
Inherits the following classes: inertialsim::geometry::MatrixLieGroup
Public Types¶
| Type | Name |
|---|---|
| typedef MatrixLieGroup< Derived, 4, 6 > | Base |
Public Types inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| typedef Eigen::Matrix< Scalar, AlgebraDimension, Eigen::Dynamic > | AlgebraArray Matrix of algebra elements (rows = axes, cols = samples). |
| typedef Eigen::Matrix< Scalar, AlgebraDimension, 1 > | AlgebraElement Algebra element type (vector). |
| typedef std::vector< GroupElement > | GroupArray Array of group elements. |
| typedef Eigen::Matrix< Scalar, GroupDimension, GroupDimension > | GroupElement Group element type (square matrix). |
| typedef Eigen::Matrix< Scalar, AlgebraDimension, AlgebraDimension > | JacobianMatrix Jacobian matrix (algebra to algebra). |
| typedef std::vector< JacobianMatrix > | JacobianMatrixArray Array of Jacobian matrices. |
Public Functions¶
| Type | Name |
|---|---|
| TransformMatrixArray | AsHomogeneousMatrix () const Return homogeneous transform matrices. |
| const Rotation & | AsRotation () const Return rotation component. |
| std::pair< Rotation, Translation > | AsRotationTranslation () const Return rotation and translation components. |
| const Translation & | AsTranslation () const Return translation component. |
| std::tuple< Vector3D, Vector3D > | Error (const RigidTransformBase< OtherDerived > & reference) const Calculate error compared to a reference transform. |
| int | num_transforms () const Number of transforms stored. |
Public Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| Vector3D | Apply (const Vector3D & vectors) const Apply the group action to an array of vectors. |
| Derived | Interpolate (const Timestamps & interp_time, Interpolator method=Interpolator::LINEAR) const Interpolate at given times. |
| Derived | Inverse () const Invert an instance. |
| Derived | Slice (int start, int end) const Get a slice of elements. |
| AlgebraArray | TimeDerivative (int order=1, int accuracy=4, const std::string & side="right") const Compute time derivative using finite differences. |
| int | num_elements () const Number of elements stored in the instance. |
| Derived | operator* (const Derived & rhs) const Composition operator on the matrix group. Supports broadcasting: if either lhs or rhs has size 1, it will be broadcast against all elements of the other operand. Derived classes may implement more efficient methods. |
| Derived | operator[] (int index) const Get a single element by index. |
| const std::optional< Timestamps > & | time () const Time array (or nullopt if not set). |
| virtual | ~MatrixLieGroup () = default |
Public Static Functions¶
| Type | Name |
|---|---|
| Derived | FromHomogeneousMatrix (const TransformMatrixArray & matrices, const std::optional< Timestamps > & time=std::nullopt, bool orthonormalize=false) Construct a RigidTransform from homogeneous transform matrices. |
| Derived | FromRotationTranslation (const Rotation & rotation, const Translation & translation, const std::optional< Timestamps > & time=std::nullopt) Construct a RigidTransform from rotation and translation. |
| Derived | FromRotationTranslation (const RotationMatrixArray & matrix, const Vector3D & xyz, const std::optional< Timestamps > & time=std::nullopt, bool orthonormalize=false) Construct from rotation matrices and translation vectors. |
Public Static Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| Derived | Compose (const std::vector< Derived > & instances) Compose a sequence of instances (first to last). |
| Derived | FromIdentity (int num_elements=1) Create identity elements. |
| Derived | FromRandom (int num_elements=1, std::optional< Eigen::numext::uint64_t > seed=std::nullopt) Create random elements. |
Protected Functions¶
| Type | Name |
|---|---|
| Vector3D | ApplyImpl (const Vector3D & vectors) const Apply transform to vectors. |
| AlgebraArray | AsAlgebraImpl () const Return as algebra elements (for CRTP interface). |
| GroupArray | AsGroupImpl () const Return as group elements (for CRTP interface). |
| Derived | InverseImpl () const Return the inverse transform. |
| RigidTransformBase () Default constructor. |
|
| RigidTransformBase (const Rotation & rotation, const Translation & translation, const std::optional< Timestamps > & time=std::nullopt) Construct from rotation and translation. |
|
| int | num_elements_impl () const Number of transforms stored. |
Protected Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| AlgebraArray | AsAlgebra () const Get the algebra elements. |
| GroupArray | AsGroup () const Get the group elements. |
| Derived | CubicHermiteInterpolate (const Timestamps & time) const Cubic Hermite spline interpolation. |
| Derived | LinearInterpolate (const Timestamps & time) const Linear interpolation implementation. |
| MatrixLieGroup (const std::optional< Timestamps > & time=std::nullopt) Constructor. |
|
| Derived & | derived () CRTP helper to access derived class. |
| const Derived & | derived () const |
| int | num_times () const |
Protected Static Functions¶
| Type | Name |
|---|---|
| GroupElement | ExpImpl (const AlgebraElement & vector) Exponential map: se(3) to SE(3). |
| Derived | FromAlgebraImpl (const AlgebraArray & algebra, const std::optional< Timestamps > & time) Construct from algebra elements (for CRTP interface). |
| Derived | FromGroupImpl (const GroupArray & elements, const std::optional< Timestamps > & time) Construct from group elements (for CRTP interface). |
| Derived | FromIdentityImpl (int num_elements) Construct identity transforms. |
| Derived | FromRandomImpl (int num_transforms, std::optional< uint64_t > seed=std::nullopt) Construct uniformly distributed random transforms. |
| Eigen::Matrix3d | JacobianAuxiliary (const Eigen::Vector3d & rv, const Eigen::Vector3d & t) Auxiliary matrix Q for SE(3) Jacobians. |
| JacobianMatrixArray | JacobianImpl (const AlgebraArray & algebra, const std::string & side="left", bool inverse=false) Left or Right Jacobian of SE(3). |
| AlgebraElement | LogImpl (const GroupElement & element) Logarithm map: SE(3) to se(3). |
Protected Static Functions inherited from inertialsim::geometry::MatrixLieGroup¶
See inertialsim::geometry::MatrixLieGroup
| Type | Name |
|---|---|
| GroupElement | Exp (const AlgebraElement & vector) Exponential map from algebra to group. |
| Derived | FromAlgebra (const AlgebraArray & elements, const std::optional< Timestamps > & time) Create instance from algebra elements. |
| Derived | FromGroup (const GroupArray & elements, const std::optional< Timestamps > & time) Create instance from group elements. |
| JacobianMatrixArray | Jacobian (const AlgebraArray & algebra, const std::string & side="left", bool inverse=false) Calculate the Jacobian given algebra elements. |
| AlgebraElement | Log (const GroupElement & element) Logarithm map from group to algebra. |
Detailed Description¶
Template parameters:
DerivedThe derived class (RigidTransform, Pose, or CoordinateTransform).
Public Types Documentation¶
typedef Base¶
Public Functions Documentation¶
function AsHomogeneousMatrix¶
Return homogeneous transform matrices.
Returns:
Vector of 4x4 matrices.
function AsRotation¶
Return rotation component.
Returns:
Rotation instance.
function AsRotationTranslation¶
Return rotation and translation components.
inline std::pair< Rotation , Translation > inertialsim::geometry::RigidTransformBase::AsRotationTranslation () const
Returns:
Tuple of Rotation and Translation.
function AsTranslation¶
Return translation component.
Returns:
Translation instance.
function Error¶
Calculate error compared to a reference transform.
template<typename OtherDerived>
inline std::tuple< Vector3D, Vector3D > inertialsim::geometry::RigidTransformBase::Error (
const RigidTransformBase < OtherDerived > & reference
) const
Parameters:
referenceReference transform.
Returns:
Tuple of rotation error and translation error.
function num_transforms¶
Number of transforms stored.
Public Static Functions Documentation¶
function FromHomogeneousMatrix¶
Construct a RigidTransform from homogeneous transform matrices.
static inline Derived inertialsim::geometry::RigidTransformBase::FromHomogeneousMatrix (
const TransformMatrixArray & matrices,
const std::optional< Timestamps > & time=std::nullopt,
bool orthonormalize=false
)
The input matrices must have 4x4 block structure [[R, t], [0, 1]] where R is a valid rotation matrix and t is a translation vector.
See Rotation::FromMatrix() for additional details regarding the rotation matrix block.
Parameters:
matricesVector of 4x4 homogeneous transform matrices.timeOptional time array of unique, strictly increasing times corresponding to each matrix input.orthonormalizeIf true, enforce orthonormality of the rotation component of the input.
Returns:
Derived instance.
function FromRotationTranslation [½]¶
Construct a RigidTransform from rotation and translation.
static inline Derived inertialsim::geometry::RigidTransformBase::FromRotationTranslation (
const Rotation & rotation,
const Translation & translation,
const std::optional< Timestamps > & time=std::nullopt
)
The inputs must be compatible (dimension, time, etc.) or a ValueError is raised.
Parameters:
rotationRotation instance.translationTranslation instance.timeOptional time array (ignored if rotation has time).
Returns:
Derived instance.
function FromRotationTranslation [2/2]¶
Construct from rotation matrices and translation vectors.
static inline Derived inertialsim::geometry::RigidTransformBase::FromRotationTranslation (
const RotationMatrixArray & matrix,
const Vector3D & xyz,
const std::optional< Timestamps > & time=std::nullopt,
bool orthonormalize=false
)
Parameters:
rotation_matricesVector of 3x3 rotation matrices.translation_xyzTranslation coordinates (3xN).timeOptional time array.orthonormalizeIf true, enforce orthonormality.
Returns:
Derived instance.
Protected Functions Documentation¶
function ApplyImpl¶
Apply transform to vectors.
inline Vector3D inertialsim::geometry::RigidTransformBase::ApplyImpl (
const Vector3D & vectors
) const
Parameters:
vectorsVectors to transform (3xN matrix).
Returns:
Transformed vectors.
function AsAlgebraImpl¶
Return as algebra elements (for CRTP interface).
Returns:
Matrix of algebra elements (6 x N).
function AsGroupImpl¶
Return as group elements (for CRTP interface).
Returns:
Vector of 4x4 matrices.
function InverseImpl¶
Return the inverse transform.
Returns:
Derived with inverted transformation.
function RigidTransformBase [½]¶
Default constructor.
function RigidTransformBase [2/2]¶
Construct from rotation and translation.
inline inertialsim::geometry::RigidTransformBase::RigidTransformBase (
const Rotation & rotation,
const Translation & translation,
const std::optional< Timestamps > & time=std::nullopt
)
Parameters:
rotationRotation component.translationTranslation component.timeOptional time array.
function num_elements_impl¶
Number of transforms stored.
Protected Static Functions Documentation¶
function ExpImpl¶
Exponential map: se(3) to SE(3).
static inline GroupElement inertialsim::geometry::RigidTransformBase::ExpImpl (
const AlgebraElement & vector
)
Parameters:
vector6D algebra element [rotation_vector, translation].
Returns:
4x4 homogeneous transform matrix.
function FromAlgebraImpl¶
Construct from algebra elements (for CRTP interface).
static inline Derived inertialsim::geometry::RigidTransformBase::FromAlgebraImpl (
const AlgebraArray & algebra,
const std::optional< Timestamps > & time
)
Parameters:
algebraAlgebra elements (N x 6 matrix).timeOptional time array.
Returns:
Derived instance.
function FromGroupImpl¶
Construct from group elements (for CRTP interface).
static inline Derived inertialsim::geometry::RigidTransformBase::FromGroupImpl (
const GroupArray & elements,
const std::optional< Timestamps > & time
)
Parameters:
elementsArray of 4x4 homogeneous transform matrices.timeOptional time array.
Returns:
Derived instance.
function FromIdentityImpl¶
Construct identity transforms.
static inline Derived inertialsim::geometry::RigidTransformBase::FromIdentityImpl (
int num_elements
)
Parameters:
num_elementsNumber of identity transforms.
Returns:
Derived instance.
function FromRandomImpl¶
Construct uniformly distributed random transforms.
static inline Derived inertialsim::geometry::RigidTransformBase::FromRandomImpl (
int num_transforms,
std::optional< uint64_t > seed=std::nullopt
)
Rotation components are uniformly distributed on the unit sphere (SO(3)). Translation components are uniformly distributed between 0 and 1.
Parameters:
num_transformsNumber of random transforms to create.seedOptional random seed for reproducibility.
Returns:
Derived instance with random transforms.
function JacobianAuxiliary¶
Auxiliary matrix Q for SE(3) Jacobians.
static inline Eigen::Matrix3d inertialsim::geometry::RigidTransformBase::JacobianAuxiliary (
const Eigen::Vector3d & rv,
const Eigen::Vector3d & t
)
Parameters:
rvRotation vector.tTranslation vector.
Returns:
3x3 auxiliary matrix.
function JacobianImpl¶
Left or Right Jacobian of SE(3).
static inline JacobianMatrixArray inertialsim::geometry::RigidTransformBase::JacobianImpl (
const AlgebraArray & algebra,
const std::string & side="left",
bool inverse=false
)
Parameters:
algebraAlgebra elements (N x 6 matrix).side"left" (default) or "right".inverseIf true, return inverse Jacobian.
Returns:
Vector of 6x6 Jacobian matrices.
function LogImpl¶
Logarithm map: SE(3) to se(3).
static inline AlgebraElement inertialsim::geometry::RigidTransformBase::LogImpl (
const GroupElement & element
)
Parameters:
element4x4 homogeneous transform matrix.
Returns:
6D algebra element [rotation_vector, translation].
The documentation for this class was generated from the following file cpp/include/inertialsim/geometry/rigid_transform_base.h