33 #include <Eigen/Geometry> 46 _R.fromRotationMatrix(iso.linear());
51 SE2(
double x,
double y,
double theta):_R(theta),_t(x,y){}
58 inline const Eigen::Rotation2Dd&
rotation()
const {
return _R;}
69 inline SE2& operator *= (
const SE2& tr2){
71 _R.angle()+=tr2.
_R.angle();
89 ret.
_t=ret.
_R*(_t*-1.);
94 inline double operator [](
int i)
const {
104 *
this=
SE2(v[0], v[1], v[2]);
109 return Vector3D(_t.x(), _t.y(), _R.angle());
114 iso.linear() = _R.toRotationMatrix();
115 iso.translation() = _t;
120 Eigen::Rotation2Dd
_R;
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
some general case utility functions
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Eigen::Transform< double, 2, Eigen::Isometry, Eigen::ColMajor > Isometry2D
Line2D operator*(const SE2 &t, const Line2D &l)
#define G2O_TYPES_SLAM2D_API
const Eigen::Rotation2Dd & rotation() const
rotational component
void fromVector(const Vector3D &v)
assign from a 3D vector (x, y, theta)
double normalize_theta(double theta)
SE2(double x, double y, double theta)
SE2(const Isometry2D &iso)
SE2 inverse() const
invert :-)
const Vector2D & translation() const
translational component
Isometry2D toIsometry() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
void setTranslation(const Vector2D &t_)
void setRotation(const Eigen::Rotation2Dd &R_)