Template Class SE2Base
Defined in File se2.hpp
Class Documentation
-
template<class Derived>
class SE2Base SE2 base type - implements SE2 class but is storage agnostic.
SE(2) is the group of rotations and translation in 2d. It is the semi-direct product of SO(2) and the 2d Euclidean vector space. The class is represented using a composition of SO2Group for rotation and a 2-vector for translation.
SE(2) is neither compact, nor a commutative group.
See SO2Group for more details of the rotation representation in 2d.
Public Types
-
using Line = ParametrizedLine2<Scalar>
-
using Hyperplane = Hyperplane2<Scalar>
-
template<typename OtherDerived>
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<Scalar, typename OtherDerived::Scalar>::ReturnType For binary operations the return type is determined with the ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map types, as well as other compatible scalar types such as Ceres::Jet and double scalars with SE2 operations.
-
template<typename OtherDerived>
using SE2Product = SE2<ReturnScalar<OtherDerived>>
-
template<typename PointDerived>
using PointProduct = Vector2<ReturnScalar<PointDerived>>
-
template<typename HPointDerived>
using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>
Public Functions
- inline SOPHUS_FUNC Adjoint Adj () const
Adjoint transformation
This function return the adjoint transformation
Ad
of the group elementA
such that for allx
it holds thathat(Ad_A * x) = A * hat(x) A^{-1}
. See hat-operator below.
- template<class NewScalarType> inline SOPHUS_FUNC SE2< NewScalarType > cast () const
Returns copy of instance casted to NewScalarType.
- inline SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0 () const
Returns derivative of this * exp(x) wrt x at x=0.
- inline SOPHUS_FUNC Matrix< Scalar, DoF, num_parameters > Dx_log_this_inv_by_x_at_this () const
Returns derivative of log(this^{-1} * x) by x at x=this.
- inline SOPHUS_FUNC SE2< Scalar > inverse () const
Returns group inverse.
- inline SOPHUS_FUNC Tangent log () const
Logarithmic map
Computes the logarithm, the inverse of the group exponential which maps element of the group (rigid body transformations) to elements of the tangent space (twist).
To be specific, this function computes
vee(logmat(.))
withlogmat(.)
being the matrix logarithm andvee(.)
the vee-operator of SE(2).
- inline SOPHUS_FUNC Transformation matrix () const
Returns 3x3 matrix representation of the instance.
It has the following form:
| R t | | o 1 |
where
R
is a 2x2 rotation matrix,t
a translation 2-vector ando
a 2-column vector of zeros.
- inline SOPHUS_FUNC Matrix< Scalar, 2, 3 > matrix2x3 () const
Returns the significant first two rows of the matrix above.
- template<class OtherDerived> inline SOPHUS_FUNC SE2Base< Derived > & operator= (SE2Base< OtherDerived > const &other)
Assignment-like operator from OtherDerived.
- template<typename OtherDerived> inline SOPHUS_FUNC SE2Product< OtherDerived > operator* (SE2Base< OtherDerived > const &other) const
Group multiplication, which is rotation concatenation.
- template<typename PointDerived, typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 2>::value>::type> inline SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const
Group action on 2-points.
This function rotates and translates a two dimensional point
p
by the SE(2) elementbar_T_foo = (bar_R_foo, t_bar)
(= rigid body transformation):p_bar = bar_R_foo * p_foo + t_bar
.
- template<typename HPointDerived, typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 3>::value>::type> inline SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
Group action on homogeneous 2-points. See above for more details.
- inline SOPHUS_FUNC Line operator* (Line const &l) const
Group action on lines.
This function rotates and translates a parametrized line
l(t) = o + t * d
by the SE(2) element:Origin
o
is rotated and translated using SE(2) action Directiond
is rotated using SO(2) action
- inline SOPHUS_FUNC Hyperplane operator* (Hyperplane const &p) const
Group action on hyper-planes.
This function rotates a hyper-plane
n.x + d = 0
by the SE2 element:Normal vector
n
is rotated Offsetd
is adjusted for translationNote that in 2d-case hyper-planes are just another parametrization of lines
- template<typename OtherDerived, typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> inline SOPHUS_FUNC SE2Base< Derived > & operator*= (SE2Base< OtherDerived > const &other)
In-place group multiplication. This method is only valid if the return type of the multiplication is compatible with this SO2’s Scalar type.
- inline SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params () const
Returns internal parameters of SE(2).
It returns (c[0], c[1], t[0], t[1]), with c being the unit complex number, t the translation 3-vector.
- inline SOPHUS_FUNC Matrix< Scalar, 2, 2 > rotationMatrix () const
Returns rotation matrix.
- inline SOPHUS_FUNC void setComplex (Sophus::Vector2< Scalar > const &complex)
Takes in complex number, and normalizes it.
Precondition: The complex number must not be close to zero.
- inline SOPHUS_FUNC void setRotationMatrix (Matrix< Scalar, 2, 2 > const &R)
Sets
so3
usingrotation_matrix
.Precondition:
R
must be orthogonal anddet(R)=1
.
- inline SOPHUS_FUNC SO2Type & so2 ()
Mutator of SO3 group.
- inline SOPHUS_FUNC SO2Type const & so2 () const
Accessor of SO3 group.
- inline SOPHUS_FUNC TranslationType & translation ()
Mutator of translation vector.
- inline SOPHUS_FUNC TranslationType const & translation () const
Accessor of translation vector
- inline SOPHUS_FUNC Eigen::internal::traits< Derived >::SO2Type::ComplexT const & unit_complex () const
Accessor of unit complex number.
Public Static Attributes
-
static constexpr int DoF = 3
Degrees of freedom of manifold, number of dimensions in tangent space (two for translation, three for rotation).
-
static constexpr int num_parameters = 4
Number of internal parameters used (tuple for complex, two for translation).
-
static constexpr int N = 3
Group transformations are 3x3 matrices.
-
static constexpr int Dim = 2
Points are 2-dimensional.
-
using Line = ParametrizedLine2<Scalar>