RIT VEXU Core API
|
#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) |
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
|
inlineconstexpr |
Default Constructor for Pose2d
Pose2d::Pose2d | ( | const Translation2d & | translation, |
const Rotation2d & | rotation ) |
Constructs a pose with given translation and rotation components.
translation | translational component. |
rotation | rotational component. |
Pose2d::Pose2d | ( | const double & | x, |
const double & | y, | ||
const Rotation2d & | rotation ) |
Constructs a pose with given translation and rotation components.
x | x component. |
y | y component. |
rotation | rotational component. |
Pose2d::Pose2d | ( | const double & | x, |
const double & | y, | ||
const double & | radians ) |
Constructs a pose with given translation and rotation components.
x | x component. |
y | y component. |
radians | rotational component in radians. |
Pose2d::Pose2d | ( | const Translation2d & | translation, |
const double & | radians ) |
Constructs a pose with given translation and rotation components.
translation | translational component. |
radians | rotational component in radians. |
Pose2d::Pose2d | ( | const Eigen::Vector3d & | pose_vector | ) |
Constructs a pose with given translation and rotation components.
pose_vector | vector of the form [x, y, theta]. |
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
old_pose | The pose to which the twist will be applied. |
twist | The twist, represents a pose delta. |
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
end_pose | the end pose to find the mapping to. |
Pose2d Pose2d::operator* | ( | const double & | scalar | ) | const |
Multiplies this pose by a scalar. Simply multiplies each component.
scalar | the scalar value to multiply by. |
Pose2d Pose2d::operator+ | ( | const Transform2d & | transform | ) | const |
Adds a transform to this pose. Transforms the pose in the pose's frame.
transform | the change in pose. |
Transform2d Pose2d::operator- | ( | const Pose2d & | other | ) | const |
Subtracts one pose from another to find the transform between them.
other | the pose to subtract. |
Pose2d Pose2d::operator/ | ( | const double & | scalar | ) | const |
Divides this pose by a scalar. Simply divides each component.
scalar | the scalar value to divide by. |
bool Pose2d::operator== | ( | const Pose2d | other | ) | const |
Compares this to another pose.
other | the other pose to compare to. |
Finds the pose equivalent to this pose relative to another arbitrary pose rather than the origin.
other | the pose representing the new origin. |
Rotation2d Pose2d::rotation | ( | ) | const |
Returns the rotational component.
void Pose2d::setRotationDeg | ( | double | rotDeg | ) |
sets the ration value of the rotational component in Degrees
void Pose2d::setRotationRad | ( | double | rotRad | ) |
sets the ration value of the rotational component in Radians
Pose2d Pose2d::transform_by | ( | const Transform2d & | transform | ) | const |
Adds a transform to this pose. Simply adds each component.
transform | the change in pose. |
Translation2d Pose2d::translation | ( | ) | const |
Returns the translational component.
double Pose2d::x | ( | ) | const |
Returns the x value of the translational component.
double Pose2d::y | ( | ) | const |
Returns the y value of the translational component.
|
friend |
Sends a pose to an output stream. Ex. std::cout << pose;
prints "Pose2d[x: (value), y: (value), rad: (radians), deg: (degrees)]"