WPILibC++ 2023.4.3
frc::Pose3d Class Reference

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

#include <frc/geometry/Pose3d.h>

Public Member Functions

constexpr Pose3d ()=default
 Constructs a pose at the origin facing toward the positive X axis. More...
 
 Pose3d (Translation3d translation, Rotation3d rotation)
 Constructs a pose with the specified translation and rotation. More...
 
 Pose3d (units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation)
 Constructs a pose with x, y, and z translations instead of a separate Translation3d. More...
 
 Pose3d (const Pose2d &pose)
 Constructs a 3D pose from a 2D pose in the X-Y plane. More...
 
Pose3d operator+ (const Transform3d &other) const
 Transforms the pose by the given transformation and returns the new transformed pose. More...
 
Transform3d operator- (const Pose3d &other) const
 Returns the Transform3d that maps the one pose to another. More...
 
bool operator== (const Pose3d &) const =default
 Checks equality between this Pose3d and another object. More...
 
const Translation3dTranslation () const
 Returns the underlying translation. More...
 
units::meter_t X () const
 Returns the X component of the pose's translation. More...
 
units::meter_t Y () const
 Returns the Y component of the pose's translation. More...
 
units::meter_t Z () const
 Returns the Z component of the pose's translation. More...
 
const Rotation3dRotation () const
 Returns the underlying rotation. More...
 
Pose3d operator* (double scalar) const
 Multiplies the current pose by a scalar. More...
 
Pose3d operator/ (double scalar) const
 Divides the current pose by a scalar. More...
 
Pose3d TransformBy (const Transform3d &other) const
 Transforms the pose by the given transformation and returns the new pose. More...
 
Pose3d RelativeTo (const Pose3d &other) const
 Returns the current pose relative to the given pose. More...
 
Pose3d Exp (const Twist3d &twist) const
 Obtain a new Pose3d from a (constant curvature) velocity. More...
 
Twist3d Log (const Pose3d &end) const
 Returns a Twist3d that maps this pose to the end pose. More...
 
Pose2d ToPose2d () const
 Returns a Pose2d representing this Pose3d projected into the X-Y plane. More...
 

Detailed Description

Represents a 3D pose containing translational and rotational elements.

Constructor & Destructor Documentation

◆ Pose3d() [1/4]

constexpr frc::Pose3d::Pose3d ( )
constexprdefault

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

◆ Pose3d() [2/4]

frc::Pose3d::Pose3d ( Translation3d  translation,
Rotation3d  rotation 
)

Constructs a pose with the specified translation and rotation.

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

◆ Pose3d() [3/4]

frc::Pose3d::Pose3d ( units::meter_t  x,
units::meter_t  y,
units::meter_t  z,
Rotation3d  rotation 
)

Constructs a pose with x, y, and z translations instead of a separate Translation3d.

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

◆ Pose3d() [4/4]

frc::Pose3d::Pose3d ( const Pose2d pose)
explicit

Constructs a 3D pose from a 2D pose in the X-Y plane.

Parameters
poseThe 2D pose.

Member Function Documentation

◆ Exp()

Pose3d frc::Pose3d::Exp ( const Twist3d twist) const

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

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 Twist3d{0.01_m, 0_m, 0_m, Rotation3d{0.0, 0.0, 0.5_deg}}.
Returns
The new pose of the robot.

◆ Log()

Twist3d frc::Pose3d::Log ( const Pose3d end) const

Returns a Twist3d 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.

◆ operator*()

Pose3d frc::Pose3d::operator* ( double  scalar) const

Multiplies the current pose by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Pose2d.

◆ operator+()

Pose3d frc::Pose3d::operator+ ( const Transform3d other) const

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

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

◆ operator-()

Transform3d frc::Pose3d::operator- ( const Pose3d other) const

Returns the Transform3d 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/()

Pose3d frc::Pose3d::operator/ ( double  scalar) const

Divides the current pose by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Pose2d.

◆ operator==()

bool frc::Pose3d::operator== ( const Pose3d ) const
default

Checks equality between this Pose3d and another object.

◆ RelativeTo()

Pose3d frc::Pose3d::RelativeTo ( const Pose3d other) const

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.

◆ Rotation()

const Rotation3d & frc::Pose3d::Rotation ( ) const
inline

Returns the underlying rotation.

Returns
Reference to the rotational component of the pose.

◆ ToPose2d()

Pose2d frc::Pose3d::ToPose2d ( ) const

Returns a Pose2d representing this Pose3d projected into the X-Y plane.

◆ TransformBy()

Pose3d frc::Pose3d::TransformBy ( const Transform3d other) const

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 Translation3d & frc::Pose3d::Translation ( ) const
inline

Returns the underlying translation.

Returns
Reference to the translational component of the pose.

◆ X()

units::meter_t frc::Pose3d::X ( ) const
inline

Returns the X component of the pose's translation.

Returns
The x component of the pose's translation.

◆ Y()

units::meter_t frc::Pose3d::Y ( ) const
inline

Returns the Y component of the pose's translation.

Returns
The y component of the pose's translation.

◆ Z()

units::meter_t frc::Pose3d::Z ( ) const
inline

Returns the Z component of the pose's translation.

Returns
The z component of the pose's translation.

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