27 #include <gtsam/dllexport.h> 28 #include <gtsam/base/std_optional_serialization.h> 45 typedef Point2 Translation;
72 r_(
Rot2::fromAngle(theta)), t_(x, y) {
77 r_(
Rot2::fromAngle(theta)), t_(t) {
85 r_(
Rot2::atan2(T(1, 0), T(0, 0))), t_(T(0, 2), T(1, 2)) {
86 assert(T.rows() == 3 && T.cols() == 3);
105 static std::optional<Pose2>
Align(
const Point2Pairs& abPointPairs);
108 static std::optional<Pose2>
Align(
const Matrix& a,
const Matrix& b);
115 GTSAM_EXPORT
void print(
const std::string& s =
"")
const;
118 GTSAM_EXPORT
bool equals(
const Pose2& pose,
double tol = 1e-9)
const;
132 return Pose2(r_*p2.
r(), t_ + r_*p2.
t());
152 inline Vector3
Adjoint(
const Vector3& xi)
const {
159 GTSAM_EXPORT
static Matrix3
adjointMap(
const Vector3& v);
164 static Vector3
adjoint(
const Vector3& xi,
const Vector3&
y) {
176 static Matrix3 adjointMap_(
const Vector3 &xi) {
return adjointMap(xi);}
177 static Vector3 adjoint_(
const Vector3 &xi,
const Vector3 &
y) {
return adjoint(xi, y);}
186 static inline Matrix3
wedge(
double vx,
double vy,
double w) {
246 inline double x()
const {
return t_.x(); }
249 inline double y()
const {
return t_.y(); }
258 inline const Rot2&
r()
const {
return r_; }
267 GTSAM_EXPORT Matrix3 matrix()
const;
329 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION // 331 friend class boost::serialization::access;
332 template<
class Archive>
333 void serialize(Archive & ar,
const unsigned int ) {
334 ar & BOOST_SERIALIZATION_NVP(t_);
335 ar & BOOST_SERIALIZATION_NVP(r_);
352 using Pose2Pair = std::pair<Pose2, Pose2>;
353 using Pose2Pairs = std::vector<Pose2Pair>;
362 template <
typename T>
365 template <
typename T>
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
GTSAM_EXPORT Matrix3 AdjointMap() const
Point2 operator*(const Point2 &point) const
Definition: Pose2.h:237
Pose2()
Definition: Pose2.h:58
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Definition: BearingRange.h:197
static Pose2 Identity()
identity for group operation
Definition: Pose2.h:125
Vector2 Point2
Definition: Point2.h:32
Pose2(const Vector &v)
Definition: Pose2.h:94
Pose2(double x, double y, double theta)
Definition: Pose2.h:71
static Matrix3 wedge(double vx, double vy, double w)
Definition: Pose2.h:186
const Point2 & t() const
translation
Definition: Pose2.h:255
const Rot2 & rotation() const
rotation
Definition: Pose2.h:264
static std::pair< size_t, size_t > translationInterval()
Definition: Pose2.h:312
double y() const
get y
Definition: Pose2.h:249
Definition: BearingRange.h:183
Pose2(const Matrix &T)
Definition: Pose2.h:84
static GTSAM_EXPORT Matrix3 ExpmapDerivative(const Vector3 &v)
Derivative of Expmap.
GTSAM_EXPORT void print(const std::string &s="") const
Pose2(const Pose2 &pose)
Definition: Pose2.h:63
const Rot2 & r() const
rotation
Definition: Pose2.h:258
double theta() const
get theta
Definition: Pose2.h:252
Matrix wedge< Pose2 >(const Vector &xi)
Definition: Pose2.h:346
static GTSAM_EXPORT Pose2 Expmap(const Vector3 &xi, ChartJacobian H={})
Exponential map at identity - create a rotation from canonical coordinates .
Definition: BearingRange.h:35
Pose2(const Rot2 &r, const Point2 &t)
Definition: Pose2.h:81
Pose2 operator*(const Pose2 &p2) const
compose syntactic sugar
Definition: Pose2.h:131
Base class and basic functions for Lie types.
Definition: BearingRange.h:41
Definition: chartTesting.h:28
static std::pair< size_t, size_t > rotationInterval()
Definition: Pose2.h:319
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
Definition: Pose2.h:152
GTSAM_EXPORT Pose2 inverse() const
inverse
static Vector3 adjointTranspose(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:171
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
static GTSAM_EXPORT Matrix3 LogmapDerivative(const Pose2 &v)
Derivative of Logmap.
Definition: OptionalJacobian.h:38
Both LieGroupTraits and Testable.
Definition: Lie.h:229
GTSAM_EXPORT Point2 transformTo(const Point2 &point, OptionalJacobian< 2, 3 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
static GTSAM_EXPORT Vector3 Logmap(const Pose2 &p, ChartJacobian H={})
Log map at identity - return the canonical coordinates of this rotation.
static GTSAM_EXPORT Matrix3 adjointMap(const Vector3 &v)
Pose2(double theta, const Point2 &t)
Definition: Pose2.h:76
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Pose2 &p)
Output stream operator.
const Point2 & translation() const
translation
Definition: Pose2.h:261
GTSAM_EXPORT bool equals(const Pose2 &pose, double tol=1e-9) const
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
double x() const
get x
Definition: Pose2.h:246
static Vector3 adjoint(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:164
Rot2 Rotation
Definition: Pose2.h:44
static std::optional< Pose2 > Align(const Point2Pairs &abPointPairs)
double theta() const
Definition: Rot2.h:186