WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::Pose2d Class Reference

Represents a 2D pose containing translational and rotational elements. More...

#include <frc/geometry/Pose2d.h>

Public Member Functions

constexpr Pose2d ()=default
 Constructs a pose at the origin facing toward the positive X axis.
 
constexpr Pose2d (Translation2d translation, Rotation2d rotation)
 Constructs a pose with the specified translation and rotation.
 
constexpr Pose2d (units::meter_t x, units::meter_t y, Rotation2d rotation)
 Constructs a pose with x and y translations instead of a separate Translation2d.
 
constexpr Pose2d (const Eigen::Matrix3d &matrix)
 Constructs a pose with the specified affine transformation matrix.
 
constexpr Pose2d operator+ (const Transform2d &other) const
 Transforms the pose by the given transformation and returns the new transformed pose.
 
constexpr Transform2d operator- (const Pose2d &other) const
 Returns the Transform2d that maps the one pose to another.
 
constexpr bool operator== (const Pose2d &) const =default
 Checks equality between this Pose2d and another object.
 
constexpr const Translation2dTranslation () const
 Returns the underlying translation.
 
constexpr units::meter_t X () const
 Returns the X component of the pose's translation.
 
constexpr units::meter_t Y () const
 Returns the Y component of the pose's translation.
 
constexpr const Rotation2dRotation () const
 Returns the underlying rotation.
 
constexpr Pose2d operator* (double scalar) const
 Multiplies the current pose by a scalar.
 
constexpr Pose2d operator/ (double scalar) const
 Divides the current pose by a scalar.
 
constexpr Pose2d RotateBy (const Rotation2d &other) const
 Rotates the pose around the origin and returns the new pose.
 
constexpr Pose2d TransformBy (const Transform2d &other) const
 Transforms the pose by the given transformation and returns the new pose.
 
constexpr Pose2d RelativeTo (const Pose2d &other) const
 Returns the current pose relative to the given pose.
 
constexpr Pose2d Exp (const Twist2d &twist) const
 Obtain a new Pose2d from a (constant curvature) velocity.
 
constexpr Twist2d Log (const Pose2d &end) const
 Returns a Twist2d that maps this pose to the end pose.
 
constexpr Eigen::Matrix3d ToMatrix () const
 Returns an affine transformation matrix representation of this pose.
 
constexpr Pose2d Nearest (std::span< const Pose2d > poses) const
 Returns the nearest Pose2d from a collection of poses.
 
constexpr Pose2d Nearest (std::initializer_list< Pose2d > poses) const
 Returns the nearest Pose2d from a collection of poses.
 

Detailed Description

Represents a 2D pose containing translational and rotational elements.

Constructor & Destructor Documentation

◆ Pose2d() [1/4]

frc::Pose2d::Pose2d ( )
constexprdefault

Constructs a pose at the origin facing toward the positive X axis.

◆ Pose2d() [2/4]

frc::Pose2d::Pose2d ( Translation2d translation,
Rotation2d rotation )
inlineconstexpr

Constructs a pose with the specified translation and rotation.

Parameters
translationThe translational component of the pose.
rotationThe rotational component of the pose.

◆ Pose2d() [3/4]

frc::Pose2d::Pose2d ( units::meter_t x,
units::meter_t y,
Rotation2d rotation )
inlineconstexpr

Constructs a pose with x and y translations instead of a separate Translation2d.

Parameters
xThe x component of the translational component of the pose.
yThe y component of the translational component of the pose.
rotationThe rotational component of the pose.

◆ Pose2d() [4/4]

frc::Pose2d::Pose2d ( const Eigen::Matrix3d & matrix)
inlineexplicitconstexpr

Constructs a pose with the specified affine transformation matrix.

Parameters
matrixThe affine transformation matrix.
Throws:
std::domain_error if the affine transformation matrix is invalid.

Member Function Documentation

◆ Exp()

Pose2d frc::Pose2d::Exp ( const Twist2d & twist) const
constexpr

Obtain a new Pose2d from a (constant curvature) velocity.

See https://file.tavsys.net/control/controls-engineering-in-frc.pdf section 10.2 "Pose exponential" for a derivation.

The twist is a change in pose in the robot's coordinate frame since the previous pose update. When the user runs exp() on the previous known field-relative pose with the argument being the twist, the user will receive the new field-relative pose.

"Exp" represents the pose exponential, which is solving a differential equation moving the pose forward in time.

Parameters
twistThe change in pose in the robot's coordinate frame since the previous pose update. For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5 degrees since the previous pose update, the twist would be Twist2d{0.01_m, 0_m, 0.5_deg}.
Returns
The new pose of the robot.

◆ Log()

Twist2d frc::Pose2d::Log ( const Pose2d & end) const
constexpr

Returns a Twist2d that maps this pose to the end pose.

If c is the output of a.Log(b), then a.Exp(c) would yield b.

Parameters
endThe end pose for the transformation.
Returns
The twist that maps this to end.

◆ Nearest() [1/2]

Pose2d frc::Pose2d::Nearest ( std::initializer_list< Pose2d > poses) const
inlineconstexpr

Returns the nearest Pose2d from a collection of poses.

Parameters
posesThe collection of poses.
Returns
The nearest Pose2d from the collection.

◆ Nearest() [2/2]

Pose2d frc::Pose2d::Nearest ( std::span< const Pose2d > poses) const
inlineconstexpr

Returns the nearest Pose2d from a collection of poses.

Parameters
posesThe collection of poses.
Returns
The nearest Pose2d from the collection.

◆ operator*()

Pose2d frc::Pose2d::operator* ( double scalar) const
inlineconstexpr

Multiplies the current pose by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Pose2d.

◆ operator+()

Pose2d frc::Pose2d::operator+ ( const Transform2d & other) const
inlineconstexpr

Transforms the pose by the given transformation and returns the new transformed pose.

[x_new]    [cos, -sin, 0][transform.x]
[y_new] += [sin,  cos, 0][transform.y]
[t_new]    [  0,    0, 1][transform.t]
Parameters
otherThe transform to transform the pose by.
Returns
The transformed pose.

◆ operator-()

Transform2d frc::Pose2d::operator- ( const Pose2d & other) const
constexpr

Returns the Transform2d that maps the one pose to another.

Parameters
otherThe initial pose of the transformation.
Returns
The transform that maps the other pose to the current pose.

◆ operator/()

Pose2d frc::Pose2d::operator/ ( double scalar) const
inlineconstexpr

Divides the current pose by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Pose2d.

◆ operator==()

bool frc::Pose2d::operator== ( const Pose2d & ) const
constexprdefault

Checks equality between this Pose2d and another object.

◆ RelativeTo()

Pose2d frc::Pose2d::RelativeTo ( const Pose2d & other) const
constexpr

Returns the current pose relative to the given pose.

This function can often be used for trajectory tracking or pose stabilization algorithms to get the error between the reference and the current pose.

Parameters
otherThe pose that is the origin of the new coordinate frame that the current pose will be converted into.
Returns
The current pose relative to the new origin pose.

◆ RotateBy()

Pose2d frc::Pose2d::RotateBy ( const Rotation2d & other) const
inlineconstexpr

Rotates the pose around the origin and returns the new pose.

Parameters
otherThe rotation to transform the pose by.
Returns
The rotated pose.

◆ Rotation()

const Rotation2d & frc::Pose2d::Rotation ( ) const
inlineconstexpr

Returns the underlying rotation.

Returns
Reference to the rotational component of the pose.

◆ ToMatrix()

Eigen::Matrix3d frc::Pose2d::ToMatrix ( ) const
inlineconstexpr

Returns an affine transformation matrix representation of this pose.

◆ TransformBy()

Pose2d frc::Pose2d::TransformBy ( const Transform2d & other) const
constexpr

Transforms the pose by the given transformation and returns the new pose.

See + operator for the matrix multiplication performed.

Parameters
otherThe transform to transform the pose by.
Returns
The transformed pose.

◆ Translation()

const Translation2d & frc::Pose2d::Translation ( ) const
inlineconstexpr

Returns the underlying translation.

Returns
Reference to the translational component of the pose.

◆ X()

units::meter_t frc::Pose2d::X ( ) const
inlineconstexpr

Returns the X component of the pose's translation.

Returns
The x component of the pose's translation.

◆ Y()

units::meter_t frc::Pose2d::Y ( ) const
inlineconstexpr

Returns the Y component of the pose's translation.

Returns
The y component of the pose's translation.

The documentation for this class was generated from the following file: