27 #include <gtsam/dllexport.h> 68 Pose2(
double x,
double y,
double theta) :
69 r_(
Rot2::fromAngle(theta)), t_(x, y) {
74 r_(
Rot2::fromAngle(theta)), t_(t) {
82 r_(
Rot2::atan2(T(1, 0), T(0, 0))), t_(T(0, 2), T(1, 2)) {
83 assert(T.rows() == 3 && T.cols() == 3);
100 void print(
const std::string& s =
"")
const;
103 bool equals(
const Pose2& pose,
double tol = 1e-9)
const;
113 Pose2 inverse()
const;
117 return Pose2(r_*p2.
r(), t_ + r_*p2.
t());
125 static Pose2 Expmap(
const Vector3& xi, ChartJacobian H = boost::none);
128 static Vector3 Logmap(
const Pose2& p, ChartJacobian H = boost::none);
134 Matrix3 AdjointMap()
const;
137 inline Vector3
Adjoint(
const Vector3& xi)
const {
138 return AdjointMap()*xi;
144 static Matrix3 adjointMap(
const Vector3& v);
149 static Vector3
adjoint(
const Vector3& xi,
const Vector3& y) {
150 return adjointMap(xi) * y;
157 return adjointMap(xi).transpose() * y;
161 static Matrix3 adjointMap_(
const Vector3 &xi) {
return adjointMap(xi);}
162 static Vector3 adjoint_(
const Vector3 &xi,
const Vector3 &y) {
return adjoint(xi, y);}
171 static inline Matrix3
wedge(
double vx,
double vy,
double w) {
180 static Matrix3 ExpmapDerivative(
const Vector3& v);
183 static Matrix3 LogmapDerivative(
const Pose2& v);
187 static Pose2 Retract(
const Vector3& v, ChartJacobian H = boost::none);
188 static Vector3 Local(
const Pose2& r, ChartJacobian H = boost::none);
215 inline double x()
const {
return t_.
x(); }
218 inline double y()
const {
return t_.
y(); }
227 inline const Rot2&
r()
const {
return r_; }
236 Matrix3 matrix()
const;
259 double range(
const Point2& point,
268 double range(
const Pose2& point,
292 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 298 return transformFrom(point, Dpose, Dpoint);
300 Point2 transform_to(
const Point2& point,
301 OptionalJacobian<2, 3> Dpose = boost::none,
302 OptionalJacobian<2, 2> Dpoint = boost::none)
const {
303 return transformTo(point, Dpose, Dpoint);
311 friend class boost::serialization::access;
312 template<
class Archive>
313 void serialize(Archive & ar,
const unsigned int ) {
314 ar & BOOST_SERIALIZATION_NVP(t_);
315 ar & BOOST_SERIALIZATION_NVP(r_);
320 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
335 GTSAM_EXPORT boost::optional<Pose2> align(
const std::vector<Point2Pair>& pairs);
344 template <
typename T>
347 template <
typename T>
static std::pair< size_t, size_t > translationInterval()
Return the start and end indices (inclusive) of the translation component of the exponential map para...
Definition: Pose2.h:281
const Point2 & t() const
translation
Definition: Pose2.h:224
Pose2(const Rot2 &r, const Point2 &t)
construct from r,t
Definition: Pose2.h:78
double theta() const
return angle (RADIANS)
Definition: Rot2.h:173
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Both LieGroupTraits and Testable.
Definition: Lie.h:237
const Rot2 & rotation() const
rotation
Definition: Pose2.h:233
Template to create a binary predicate.
Definition: Testable.h:110
Pose2()
default constructor = origin
Definition: Pose2.h:55
static Pose2 identity()
identity for group operation
Definition: Pose2.h:110
Definition: BearingRange.h:33
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
const Point2 & translation() const
translation
Definition: Pose2.h:230
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:36
Definition: BearingRange.h:193
static Vector3 adjoint(const Vector3 &xi, const Vector3 &y)
Action of the adjointMap on a Lie-algebra vector y, with optional derivatives.
Definition: Pose2.h:149
double x() const
get x
Definition: Pose2.h:215
Pose2(double theta, const Point2 &t)
construct from rotation and translation
Definition: Pose2.h:73
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
Definition: Pose2.h:137
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
double y() const
get y
Definition: Point2.h:106
Definition: BearingRange.h:179
Definition: BearingRange.h:39
Matrix wedge< Pose2 >(const Vector &xi)
specialization for pose2 wedge function (generic template in Lie.h)
Definition: Pose2.h:325
static Vector3 adjointTranspose(const Vector3 &xi, const Vector3 &y)
The dual version of adjoint action, acting on the dual space of the Lie-algebra vector space.
Definition: Pose2.h:156
double y() const
get y
Definition: Pose2.h:218
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Pose2(const Pose2 &pose)
copy constructor
Definition: Pose2.h:60
const Rot2 & r() const
rotation
Definition: Pose2.h:227
Rot2 Rotation
Pose Concept requirements.
Definition: Pose2.h:41
Base class and basic functions for Lie types.
Pose2(const Vector &v)
Construct from canonical coordinates (Lie algebra)
Definition: Pose2.h:91
std::pair< Point2, Point2 > Point2Pair
Calculate pose between a vector of 2D point correspondences (p,q) where q = Pose2::transformFrom(p) =...
Definition: Point2.h:163
static std::pair< size_t, size_t > rotationInterval()
Return the start and end indices (inclusive) of the rotation component of the exponential map paramet...
Definition: Pose2.h:288
Pose2(const Matrix &T)
Constructor from 3*3 matrix.
Definition: Pose2.h:81
Point2 operator *(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:170
double x() const
get x
Definition: Point2.h:103
double theta() const
get theta
Definition: Pose2.h:221
Pose2(double x, double y, double theta)
construct from (x,y,theta)
Definition: Pose2.h:68
static Matrix3 wedge(double vx, double vy, double w)
wedge for SE(2):
Definition: Pose2.h:171