27#ifndef G2O_TUTORIAL_SE2_H
28#define G2O_TUTORIAL_SE2_H
31#include <Eigen/Geometry>
45 SE2() : _R(0), _t(0, 0) {}
47 SE2(
double x,
double y,
double theta) : _R(theta), _t(x, y) {}
53 const Eigen::Rotation2Dd&
rotation()
const {
return _R; }
59 result.
_t += _R * tr2.
_t;
60 result.
_R.angle() += tr2.
_R.angle();
67 _R.angle() += tr2.
_R.angle();
72 Eigen::Vector2d
operator*(
const Eigen::Vector2d& v)
const {
78 ret.
_R = _R.inverse();
80 ret.
_t = ret.
_R * (Eigen::Vector2d(-1 * _t));
85 assert(i >= 0 && i < 3);
86 if (i < 2)
return _t(i);
91 assert(i >= 0 && i < 3);
92 if (i < 2)
return _t(i);
96 void fromVector(
const Eigen::Vector3d& v) { *
this =
SE2(v[0], v[1], v[2]); }
100 for (
int i = 0; i < 3; i++) {
107 Eigen::Rotation2Dd
_R;
SE2 operator*(const SE2 &tr2) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
SE2 & operator*=(const SE2 &tr2)
SE2(double x, double y, double theta)
const Eigen::Vector2d & translation() const
Eigen::Vector2d operator*(const Eigen::Vector2d &v) const
double & operator[](int i)
const Eigen::Rotation2Dd & rotation() const
double operator[](int i) const
Eigen::Rotation2Dd & rotation()
Eigen::Vector3d toVector() const
Eigen::Vector2d & translation()
void fromVector(const Eigen::Vector3d &v)
#define G2O_TUTORIAL_SLAM2D_API
some general case utility functions
double normalize_theta(double theta)