Struct TPose2D
Defined in File TPose2D.h
Inheritance Relationships
Base Types
public mrpt::math::TPoseOrPoint(Struct TPoseOrPoint)public mrpt::math::internal::ProvideStaticResize< TPose2D >(Template Struct ProvideStaticResize)
Struct Documentation
-
struct TPose2D : public mrpt::math::TPoseOrPoint, public mrpt::math::internal::ProvideStaticResize<TPose2D>
Lightweight 2D rigid-body pose — an element of SE(2).
Parameterises the group SE(2) = SO(2) ⋉ R² as the triplet
(x, y, φ):(x, y)— translation in metres.φ(phi) — counter-clockwise rotation angle in radians, measured from the global X axis.
The equivalent 3x3 homogeneous matrix is:
* T = | cos(phi) -sin(phi) x | * | sin(phi) cos(phi) y | * | 0 0 1 | *
**Composition (
operator+)** implements the SE(2) group product:(this ⊕ b)maps a point expressed in framebinto the frame ofthis.**Inverse composition (
operator-)** implements(this ⊖ b) = b⁻¹ ⊕ this, i.e. the pose ofthisexpressed in the frame ofb.This is a lightweight type without serialization or caching of trig values. Prefer mrpt::poses::CPose2D when composition is called repeatedly with the same pose (it caches cos/sin and supports serialization).
Coordinate access:
operator[]with index 0→x, 1→y, 2→phi.See also
Public Functions
-
explicit TPose2D(const TPoint2D &p)
Constructor from TPoint2D: copies (x,y), sets phi=0 (pure translation, no rotation).
-
explicit TPose2D(const TPoint3D &p)
Constructor from TPoint3D: copies (x,y), sets phi=0; the z coordinate is discarded.
-
explicit TPose2D(const TPose3D &p)
Constructor from TPose3D: copies (x,y), maps yaw→phi; z, pitch and roll are discarded. This is a projection from SE(3) onto SE(2); information is irreversibly lost when pitch ≠ 0 or roll ≠ 0.
See also
-
inline constexpr TPose2D(double xx, double yy, double Phi)
Constructor from coordinates.
-
constexpr TPose2D() = default
Default fast constructor. Initializes to zeros.
-
inline double &operator[](size_t i)
Coordinate access using operator[]. Order: x,y,phi
-
inline constexpr double operator[](size_t i) const
Coordinate access using operator[]. Order: x,y,phi
-
template<typename Vector>
inline void asVector(Vector &v) const Gets the pose as a vector of doubles.
- Template Parameters:
Vector – It can be std::vector<double>, Eigen::VectorXd, etc.
-
template<typename Vector>
inline Vector asVector() const This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
-
void asString(std::string &s) const
Returns a human-readable textual representation of the object (eg: “[x y
yaw]”, yaw in degrees)
See also
-
inline std::string asString() const
-
mrpt::math::TPose2D operator+(const mrpt::math::TPose2D &b) const
SE(2) group composition — “⊕” operator:
ret = this ⊕ b.Computes the pose obtained by first applying transformation
this, thenb. In matrix form:T_ret = T_this · T_b. Ifthisis the pose of frame A in the world W, andbis the pose of frame B in frame A, thenretis the pose of B in W.See also
CPose2D, inverseComposeFrom
-
mrpt::math::TPose2D operator-(const mrpt::math::TPose2D &b) const
SE(2) inverse composition — “⊖” operator:
ret = this ⊖ b = b⁻¹ ⊕ this.Returns the pose of
thisexpressed in the reference frame ofb. In matrix form:T_ret = T_b⁻¹ · T_this. Useful for computing relative poses: if boththisandbare poses in the world frame,retis the pose ofthisas seen fromb.See also
CPose2D
-
mrpt::math::TPoint2D composePoint(const TPoint2D l) const
Transforms a point from the local frame of this pose into the global (world) frame. Equivalent to
g = T_this · [l.x l.y 1]ᵀ(homogeneous coords).See also
- Parameters:
l – Point in the local frame.
- Returns:
Point in the global frame.
-
mrpt::math::TPoint2D operator+(const mrpt::math::TPoint2D &b) const
Alias for composePoint():
pose + pointapplies the SE(2) transformation to the point.
-
mrpt::math::TPoint2D inverseComposePoint(const TPoint2D g) const
Transforms a point from the global (world) frame into the local frame of this pose. Equivalent to
l = T_this⁻¹ · [g.x g.y 1]ᵀ(homogeneous coords).See also
- Parameters:
g – Point in the global frame.
- Returns:
Point in the local frame of this pose.
-
inline const mrpt::math::TPoint2D translation() const
Returns the (x,y) translational part of the SE(2) transformation.
-
inline double norm() const
Euclidean norm of the translational part: |(x,y)|. The angle phi is ignored.
-
inline void normalizePhi()
Wraps phi to the canonical range (-pi, pi].
Public Members
-
double x = {.0}
Translation along the global X axis (metres).
-
double y = {.0}
Translation along the global Y axis (metres).
-
double phi = {.0}
Heading angle phi in radians, counter-clockwise from the global X axis. Range: any real value; use normalizePhi() to wrap to (-pi, pi].
Public Static Functions
Public Static Attributes
-
static constexpr std::size_t static_size = 3