27 #ifndef G2O_TUTORIAL_SE2_H 28 #define G2O_TUTORIAL_SE2_H 36 #include <Eigen/Geometry> 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 {
80 ret.
_t=ret.
_R*(Eigen::Vector2d(-1 * _t));
84 double operator [](
int i)
const {
91 double& operator [](
int i) {
99 *
this=
SE2(v[0], v[1], v[2]);
104 for (
int i=0; i<3; i++){
111 Eigen::Rotation2Dd
_R;
Eigen::Vector2d & translation()
SE2(double x, double y, double theta)
some general case utility functions
const Eigen::Rotation2Dd & rotation() const
Line2D operator*(const SE2 &t, const Line2D &l)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Eigen::Vector3d toVector() const
void fromVector(const Eigen::Vector3d &v)
Eigen::Rotation2Dd & rotation()
const Eigen::Vector2d & translation() const
#define G2O_TUTORIAL_SLAM2D_API
double normalize_theta(double theta)