|
| SOPHUS_FUNC Adjoint | Adj () const |
| |
| template<class NewScalarType > |
| SOPHUS_FUNC SE2< NewScalarType > | cast () const |
| |
| SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > | Dx_this_mul_exp_x_at_0 () const |
| |
| SOPHUS_FUNC SE2< Scalar > | inverse () const |
| |
| SOPHUS_FUNC Tangent | log () const |
| |
| SOPHUS_FUNC Transformation | matrix () const |
| |
| SOPHUS_FUNC Matrix< Scalar, 2, 3 > | matrix2x3 () const |
| |
| SOPHUS_FUNC void | normalize () |
| |
| template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 3>::value>::type> |
| SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > | operator* (Eigen::MatrixBase< HPointDerived > const &p) const |
| |
| template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 2>::value>::type> |
| SOPHUS_FUNC PointProduct< PointDerived > | operator* (Eigen::MatrixBase< PointDerived > const &p) const |
| |
| SOPHUS_FUNC Line | operator* (Line const &l) const |
| |
| template<typename OtherDerived > |
| SOPHUS_FUNC SE2Product< OtherDerived > | operator* (SE2Base< OtherDerived > const &other) const |
| |
| template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> |
| SOPHUS_FUNC SE2Base< Derived > & | operator*= (SE2Base< OtherDerived > const &other) |
| |
| SOPHUS_FUNC SE2Base & | operator= (SE2Base const &other)=default |
| |
| template<class OtherDerived > |
| SOPHUS_FUNC SE2Base< Derived > & | operator= (SE2Base< OtherDerived > const &other) |
| |
| SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const |
| |
| SOPHUS_FUNC Matrix< Scalar, 2, 2 > | rotationMatrix () const |
| |
| SOPHUS_FUNC void | setComplex (Sophus::Vector2< Scalar > const &complex) |
| |
| SOPHUS_FUNC void | setRotationMatrix (Matrix< Scalar, 2, 2 > const &R) |
| |
| SOPHUS_FUNC SO2Type & | so2 () |
| |
| SOPHUS_FUNC SO2Type const & | so2 () const |
| |
| SOPHUS_FUNC TranslationType & | translation () |
| |
| SOPHUS_FUNC TranslationType const & | translation () const |
| |
| SOPHUS_FUNC Eigen::internal::traits< Derived >::SO2Type::ComplexT const & | unit_complex () const |
| |
template<class Derived>
class Sophus::SE2Base< Derived >
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.
Definition at line 58 of file se2.hpp.
template<class Derived >
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 2>::value>::type>
Group action on 2-points.
This function rotates and translates a two dimensional point p by the SE(2) element bar_T_foo = (bar_R_foo, t_bar) (= rigid body transformation):
p_bar = bar_R_foo * p_foo + t_bar.
Definition at line 250 of file se2.hpp.