RIT VEXU Core API
|
#include <transform2d.h>
Public Member Functions | |
constexpr | Transform2d () |
Transform2d (const Translation2d &translation, const Rotation2d &rotation) | |
Transform2d (const double &x, const double &y, const Rotation2d &rotation) | |
Transform2d (const double &x, const double &y, const double &radians) | |
Transform2d (const Translation2d &translation, const double &radians) | |
Transform2d (const Eigen::Vector3d &transform_vector) | |
Transform2d (const Pose2d &start, const Pose2d &end) | |
Translation2d | translation () const |
double | x () const |
double | y () const |
Rotation2d | rotation () const |
Transform2d | inverse () const |
Transform2d | operator* (const double &scalar) const |
Transform2d | operator/ (const double &scalar) const |
Transform2d | operator- () const |
bool | operator== (const Transform2d &other) const |
Friends | |
std::ostream & | operator<< (std::ostream &os, const Transform2d &transform) |
Class representing a transformation of a pose2d, or a linear difference between the components of poses.
Assumes conventional cartesian coordinate system: Looking down at the coordinate plane, +X is right +Y is up +Theta is counterclockwise
|
constexpr |
Default Constructor for Transform2d
Transform2d::Transform2d | ( | const Translation2d & | translation, |
const Rotation2d & | rotation ) |
Constructs a transform given translation and rotation components.
translation | the translational component of the transform. |
rotation | the rotational component of the transform. |
Transform2d::Transform2d | ( | const double & | x, |
const double & | y, | ||
const Rotation2d & | rotation ) |
Constructs a transform given translation and rotation components.
x | the x component of the transform. |
y | the y component of the transform. |
rotation | the rotational component of the transform. |
Transform2d::Transform2d | ( | const double & | x, |
const double & | y, | ||
const double & | radians ) |
Constructs a transform given translation and rotation components.
x | the x component of the transform. |
y | the y component of the transform. |
radians | the rotational component of the transform in radians. |
Transform2d::Transform2d | ( | const Translation2d & | translation, |
const double & | radians ) |
Constructs a transform given translation and rotation components.
translation | the translational component of the transform. |
radians | the rotational component of the transform in radians. |
Transform2d::Transform2d | ( | const Eigen::Vector3d & | transform_vector | ) |
Constructs a transform given translation and rotation components given as a vector.
transform_vector | vector of the form [x, y, theta] |
Constructs a transform given translation and rotation components.
translation | the translational component of the transform. |
rotation | the rotational component of the transform. |
Transform2d Transform2d::inverse | ( | ) | const |
Inverts the transform.
Transform2d Transform2d::operator* | ( | const double & | scalar | ) | const |
Multiplies this transform by a scalar.
scalar | the scalar to multiply this transform by. |
Transform2d Transform2d::operator- | ( | ) | const |
Inverts the transform.
Transform2d Transform2d::operator/ | ( | const double & | scalar | ) | const |
Divides this transform by a scalar.
scalar | the scalar to divide this transform by. |
bool Transform2d::operator== | ( | const Transform2d & | other | ) | const |
Compares this to another transform.
other | the other transform to compare to. |
Rotation2d Transform2d::rotation | ( | ) | const |
Returns the rotational component of the transform.
Translation2d Transform2d::translation | ( | ) | const |
Returns the translational component of the transform.
double Transform2d::x | ( | ) | const |
Returns the x component of the transform.
double Transform2d::y | ( | ) | const |
Returns the y component of the transform.
|
friend |
Sends a transform to an output stream. Ex. std::cout << transform;
prints "Transform2d[dx: (value), dy: (value), drad: (radians), ddeg: (degrees)]"
Sends a transform to an output stream. Ex. std::cout << transform;
prints "Transform2d[x: (value), y: (value), rad: (radians), deg: (degrees)]"