template<typename _Derived>
SE3Base struct
The base class of the SE3 group.
Base classes
-
template<class _Derived>struct LieGroupBase<_Derived>
- Base class for Lie groups. Defines the minimum common API.
Public types
-
using Rotation = typename internal::
traits<_Derived>::Rotation -
using Translation = typename internal::
traits<_Derived>::Translation -
using Transformation = typename internal::
traits<_Derived>::Transformation - using Isometry = Eigen::Transform<Scalar, 3, Eigen::Isometry>
- using QuaternionDataType = Eigen::Quaternion<Scalar>
Public functions
- auto inverse(OptJacobianRef J_minv_m = {}) const -> LieGroup
- Get the inverse.
- auto log(OptJacobianRef J_t_m = {}) const -> Tangent
- Get the SE3 corresponding Lie algebra element in vector form.
- auto lift(OptJacobianRef J_t_m = {}) const -> MANIF_DEPRECATED Tangent
- This function is deprecated. Please considere using log instead.
-
template<typename _DerivedOther>auto compose(const LieGroupBase<_DerivedOther>& m, OptJacobianRef J_mc_ma = {}, OptJacobianRef J_mc_mb = {}) const -> LieGroup
- Composition of this and another SE3 element.
-
template<typename _EigenDerived>auto act(const Eigen::MatrixBase<_EigenDerived>& v, tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 6>>> J_vout_m = {}, tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_v = {}) const -> Eigen::Matrix<Scalar, 3, 1>
- Rigid motion action on a 3D point.
- auto adj() const -> Jacobian
- Get the adjoint matrix of SE3 at this.
- auto transform() const -> Transformation
- auto isometry() const -> Isometry
- auto rotation() const -> Rotation
- Get the rotational part of this as a rotation matrix.
- auto quat() const -> QuaternionDataType
- Get the rotational part of this as a quaternion.
- auto translation() const -> Translation
- Get the translational part in vector form.
- auto x() const -> Scalar
- Get the x component of the translational part.
- auto y() const -> Scalar
- Get the y component of translational part.
- auto z() const -> Scalar
- Get the z component of translational part.
- void normalize()
- Normalize the underlying quaternion.
- void quat(const QuaternionDataType& quaternion)
- Set the rotational as a quaternion.
-
template<typename _EigenDerived>void quat(const Eigen::MatrixBase<_EigenDerived>& quaternion)
- Set the rotational as a quaternion.
- void quat(const SO3<Scalar>& so3)
- Set the rotational as a so3 object.
- void translation(const Translation& translation)
- Set the translation of the SE3 object.
- auto asSO3() const -> Eigen::Map<const SO3<Scalar>>
- auto asSO3() -> Eigen::Map<SO3<Scalar>>
-
template<typename _EigenDerived>auto act(const Eigen::MatrixBase<_EigenDerived>& v, tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 6>>> J_vout_m, tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_v) const -> Eigen::Matrix<typename SE3Base<_Derived>::Scalar, 3, 1>
- auto coeffs() -> DataType&
- Access the underlying data by const reference.
- auto coeffs() const -> const DataType&
- Access the underlying data by const reference.
Protected functions
Function documentation
template<typename _Derived>
LieGroup manif:: SE3Base<_Derived>:: inverse(OptJacobianRef J_minv_m = {}) const
Get the inverse.
template<typename _Derived>
template<typename _DerivedOther>
LieGroup manif:: SE3Base<_Derived>:: compose(const LieGroupBase<_DerivedOther>& m,
OptJacobianRef J_mc_ma = {},
OptJacobianRef J_mc_mb = {}) const
Composition of this and another SE3 element.
Parameters | |
---|---|
m in | Another SE3 element. |
J_mc_ma | |
J_mc_mb | |
Returns | The composition of 'this . m'. |
template<typename _Derived>
template<typename _EigenDerived>
Eigen::Matrix<Scalar, 3, 1> manif:: SE3Base<_Derived>:: act(const Eigen::MatrixBase<_EigenDerived>& v,
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 6>>> J_vout_m = {},
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_v = {}) const
Rigid motion action on a 3D point.
Parameters | |
---|---|
v | A 3D point. |
J_vout_m | |
J_vout_v | |
Returns | The transformed 3D point. |
template<typename _Derived>
Transformation manif:: SE3Base<_Derived>:: transform() const
Get the transformation matrix (3D isometry).
template<typename _Derived>
Isometry manif:: SE3Base<_Derived>:: isometry() const
Get the isometry object (Eigen 3D isometry).
template<typename _Derived>
void manif:: SE3Base<_Derived>:: quat(const QuaternionDataType& quaternion)
Set the rotational as a quaternion.
Parameters | |
---|---|
quaternion | a unitary quaternion |
template<typename _Derived>
template<typename _EigenDerived>
void manif:: SE3Base<_Derived>:: quat(const Eigen::MatrixBase<_EigenDerived>& quaternion)
Set the rotational as a quaternion.
Parameters | |
---|---|
quaternion | an Eigen::Vector representing a unitary quaternion |
template<typename _Derived>
void manif:: SE3Base<_Derived>:: quat(const SO3<Scalar>& so3)
Set the rotational as a so3 object.
Parameters | |
---|---|
so3 | a manif:: |
template<typename _Derived>
void manif:: SE3Base<_Derived>:: translation(const Translation& translation)
Set the translation of the SE3 object.
Parameters | |
---|---|
translation | representing the translation |