Template Class SE2
Defined in File se2.hpp
Inheritance Relationships
Base Type
public Sophus::SE2Base< SE2< Scalar_, Options > >
(Template Class SE2Base)
Class Documentation
-
template<class Scalar_, int Options>
class SE2 : public Sophus::SE2Base<SE2<Scalar_, Options>> SE2 using default storage; derived from SE2Base.
Public Types
Public Functions
- SOPHUS_FUNC SE2 & operator= (SE2 const &other)=default
Define copy-assignment operator explicitly. The definition of implicit copy assignment operator is deprecated in presence of a user-declared copy constructor (-Wdeprecated-copy in clang >= 13).
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SE2 ()
Default constructor initializes rigid body motion to the identity.
-
template<class OtherDerived>
inline SOPHUS_FUNC SE2(SE2Base<OtherDerived> const &other) Copy-like constructor from OtherDerived
-
template<class OtherDerived, class D>
inline SOPHUS_FUNC SE2(SO2Base<OtherDerived> const &so2, Eigen::MatrixBase<D> const &translation) Constructor from SO3 and translation vector
-
inline SOPHUS_FUNC SE2(typename SO2<Scalar>::Transformation const &rotation_matrix, Point const &translation)
Constructor from rotation matrix and translation vector
Precondition: Rotation matrix needs to be orthogonal with determinant of 1.
-
inline SOPHUS_FUNC SE2(Scalar const &theta, Point const &translation)
Constructor from rotation angle and translation vector.
-
inline SOPHUS_FUNC SE2(Vector2<Scalar> const &complex, Point const &translation)
Constructor from complex number and translation vector
Precondition:
complex
must not be close to zero.
-
inline explicit SOPHUS_FUNC SE2(Transformation const &T)
Constructor from 3x3 matrix
Precondition: Rotation matrix needs to be orthogonal with determinant of 1. The last row must be
(0, 0, 1)
.
- inline SOPHUS_FUNC Scalar * data ()
This provides unsafe read/write access to internal data. SO(2) is represented by a complex number (two parameters). When using direct write access, the user needs to take care of that the complex number stays normalized.
- inline SOPHUS_FUNC Scalar const * data () const
Const version of data() above.
- inline SOPHUS_FUNC SO2Member & so2 ()
Accessor of SO3
- inline SOPHUS_FUNC SO2Member const & so2 () const
Mutator of SO3
- inline SOPHUS_FUNC TranslationMember & translation ()
Mutator of translation vector
- inline SOPHUS_FUNC TranslationMember const & translation () const
Accessor of translation vector
Public Static Functions
- static inline SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x (Tangent const &upsilon_theta)
Returns derivative of exp(x) wrt. x.
- static inline SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x_at_0 ()
Returns derivative of exp(x) wrt. x_i at x=0.
- static inline SOPHUS_FUNC Sophus::Matrix< Scalar, 2, DoF > Dx_exp_x_times_point_at_0 (Point const &point)
Returns derivative of exp(x) * p wrt. x_i at x=0.
- static inline SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0 (int i)
Returns derivative of exp(x).matrix() wrt.
x_i at x=0
.
- static inline SOPHUS_FUNC SE2< Scalar > exp (Tangent const &a)
Group exponential
This functions takes in an element of tangent space (= twist
a
) and returns the corresponding element of the group SE(2).The first two components of
a
represent the translational partupsilon
in the tangent space of SE(2), while the last three components ofa
represents the rotation vectoromega
. To be more specific, this function computesexpmat(hat(a))
withexpmat(.)
being the matrix exponential andhat(.)
the hat-operator of SE(2), see below.
- template<class S = Scalar> static inline SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE2 > fitToSE2 (Matrix3< Scalar > const &T)
Returns closest SE3 given arbitrary 4x4 matrix.
- static inline SOPHUS_FUNC Transformation generator (int i)
Returns the ith infinitesimal generators of SE(2).
The infinitesimal generators of SE(2) are:
| 0 0 1 | G_0 = | 0 0 0 | | 0 0 0 | | 0 0 0 | G_1 = | 0 0 1 | | 0 0 0 | | 0 -1 0 | G_2 = | 1 0 0 | | 0 0 0 |
Precondition:
i
must be in 0, 1 or 2.
- static inline SOPHUS_FUNC Transformation hat (Tangent const &a)
hat-operator
It takes in the 3-vector representation (= twist) and returns the corresponding matrix representation of Lie algebra element.
Formally, the hat()-operator of SE(3) is defined as
hat(.): R^3 -> R^{3x33}, hat(a) = sum_i a_i * G_i
(for i=0,1,2)with
G_i
being the ith infinitesimal generator of SE(2).The corresponding inverse is the vee()-operator, see below.
- static inline SOPHUS_FUNC Tangent lieBracket (Tangent const &a, Tangent const &b)
Lie bracket
It computes the Lie bracket of SE(2). To be more specific, it computes
[omega_1, omega_2]_se2 := vee([hat(omega_1), hat(omega_2)])
with
[A,B] := AB-BA
being the matrix commutator,hat(.)
the hat()-operator andvee(.)
the vee()-operator of SE(2).
- static inline SOPHUS_FUNC SE2 rot (Scalar const &x)
Construct pure rotation.
-
template<class UniformRandomBitGenerator>
static inline SE2 sampleUniform(UniformRandomBitGenerator &generator) Draw uniform sample from SE(2) manifold.
Translations are drawn component-wise from the range [-1, 1].
- template<class T0, class T1> static inline SOPHUS_FUNC SE2 trans (T0 const &x, T1 const &y)
Construct a translation only SE(2) instance.
- static inline SOPHUS_FUNC SE2 trans (Vector2< Scalar > const &xy)
- static inline SOPHUS_FUNC SE2 transX (Scalar const &x)
Construct x-axis translation.
- static inline SOPHUS_FUNC SE2 transY (Scalar const &y)
Construct y-axis translation.
- static inline SOPHUS_FUNC Tangent vee (Transformation const &Omega)
vee-operator
It takes the 3x3-matrix representation
Omega
and maps it to the corresponding 3-vector representation of Lie algebra.This is the inverse of the hat()-operator, see above.
Precondition:
Omega
must have the following structure:| 0 -d a | | d 0 b | | 0 0 0 |
Public Static Attributes