RIT VEXU Core API
Loading...
Searching...
No Matches
Pose2d Class Reference

#include <pose2d.h>

Public Member Functions

constexpr Pose2d ()
 
 Pose2d (const Translation2d &translation, const Rotation2d &rotation)
 
 Pose2d (const double &x, const double &y, const Rotation2d &rotation)
 
 Pose2d (const double &x, const double &y, const double &radians)
 
 Pose2d (const Translation2d &translation, const double &radians)
 
 Pose2d (const Eigen::Vector3d &pose_vector)
 
Translation2d translation () const
 
double x () const
 
double y () const
 
Rotation2d rotation () const
 
void setRotationRad (double rotRad)
 
void setRotationDeg (double rotDeg)
 
bool operator== (const Pose2d other) const
 
Pose2d operator* (const double &scalar) const
 
Pose2d operator/ (const double &scalar) const
 
Pose2d operator+ (const Transform2d &transform) const
 
Transform2d operator- (const Pose2d &other) const
 
Pose2d relative_to (const Pose2d &other) const
 
Pose2d transform_by (const Transform2d &transform) const
 
Pose2d exp (const Twist2d &twist) const
 
Twist2d log (const Pose2d &end_pose) const
 

Friends

std::ostream & operator<< (std::ostream &os, const Pose2d &pose)
 

Detailed Description

Class representing a pose in 2d space with x, y, and rotational components

Assumes conventional cartesian coordinate system: Looking down at the coordinate plane, +X is right +Y is up +Theta is counterclockwise

Constructor & Destructor Documentation

◆ Pose2d() [1/6]

Pose2d::Pose2d ( )
inlineconstexpr

Default Constructor for Pose2d

◆ Pose2d() [2/6]

Pose2d::Pose2d ( const Translation2d & translation,
const Rotation2d & rotation )

Constructs a pose with given translation and rotation components.

Parameters
translationtranslational component.
rotationrotational component.

◆ Pose2d() [3/6]

Pose2d::Pose2d ( const double & x,
const double & y,
const Rotation2d & rotation )

Constructs a pose with given translation and rotation components.

Parameters
xx component.
yy component.
rotationrotational component.

◆ Pose2d() [4/6]

Pose2d::Pose2d ( const double & x,
const double & y,
const double & radians )

Constructs a pose with given translation and rotation components.

Parameters
xx component.
yy component.
radiansrotational component in radians.

◆ Pose2d() [5/6]

Pose2d::Pose2d ( const Translation2d & translation,
const double & radians )

Constructs a pose with given translation and rotation components.

Parameters
translationtranslational component.
radiansrotational component in radians.

◆ Pose2d() [6/6]

Pose2d::Pose2d ( const Eigen::Vector3d & pose_vector)

Constructs a pose with given translation and rotation components.

Parameters
pose_vectorvector of the form [x, y, theta].

Member Function Documentation

◆ exp()

Pose2d Pose2d::exp ( const Twist2d & twist) const

Applies a twist (pose delta) to a pose by including first order dynamics of heading.

When applying a twist, imagine a constant angular velocity, the translational components must be rotated into the global frame at every point along the twist, simply adding the deltas does not do this, and using euler integration results in some error. This is the analytic solution that that problem.

Can also be thought of more simply as applying a twist as following an arc rather than a straight line.

See this document for more information on the pose exponential and its derivation. https://file.tavsys.net/control/controls-engineering-in-frc.pdf#section.10.2

Parameters
old_poseThe pose to which the twist will be applied.
twistThe twist, represents a pose delta.
Returns
new pose that has been moved forward according to the twist.

◆ log()

Twist2d Pose2d::log ( const Pose2d & end_pose) const

The inverse of the pose exponential.

Determines the twist required to go from this pose to the given end pose. suppose you have Pose2d a, Twist2d twist if a.exp(twist) = b then a.log(b) = twist

Parameters
end_posethe end pose to find the mapping to.
Returns
the twist required to go from this pose to the given end

◆ operator*()

Pose2d Pose2d::operator* ( const double & scalar) const

Multiplies this pose by a scalar. Simply multiplies each component.

Parameters
scalarthe scalar value to multiply by.

◆ operator+()

Pose2d Pose2d::operator+ ( const Transform2d & transform) const

Adds a transform to this pose. Transforms the pose in the pose's frame.

Parameters
transformthe change in pose.

◆ operator-()

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

Subtracts one pose from another to find the transform between them.

Parameters
otherthe pose to subtract.

◆ operator/()

Pose2d Pose2d::operator/ ( const double & scalar) const

Divides this pose by a scalar. Simply divides each component.

Parameters
scalarthe scalar value to divide by.

◆ operator==()

bool Pose2d::operator== ( const Pose2d other) const

Compares this to another pose.

Parameters
otherthe other pose to compare to.
Returns
true if each of the components are within 1e-9 of each other.

◆ relative_to()

Pose2d Pose2d::relative_to ( const Pose2d & other) const

Finds the pose equivalent to this pose relative to another arbitrary pose rather than the origin.

Parameters
otherthe pose representing the new origin.
Returns
this pose relative to another pose.

◆ rotation()

Rotation2d Pose2d::rotation ( ) const

Returns the rotational component.

Returns
the rotational component.

◆ setRotationDeg()

void Pose2d::setRotationDeg ( double rotDeg)

sets the ration value of the rotational component in Degrees

◆ setRotationRad()

void Pose2d::setRotationRad ( double rotRad)

sets the ration value of the rotational component in Radians

◆ transform_by()

Pose2d Pose2d::transform_by ( const Transform2d & transform) const

Adds a transform to this pose. Simply adds each component.

Parameters
transformthe change in pose.
Returns
the pose after being transformed.

◆ translation()

Translation2d Pose2d::translation ( ) const

Returns the translational component.

Returns
the translational component.

◆ x()

double Pose2d::x ( ) const

Returns the x value of the translational component.

Returns
the x value of the translational component.

◆ y()

double Pose2d::y ( ) const

Returns the y value of the translational component.

Returns
the y value of the translational component.

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream & os,
const Pose2d & pose )
friend

Sends a pose to an output stream. Ex. std::cout << pose;

prints "Pose2d[x: (value), y: (value), rad: (radians), deg: (degrees)]"


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