RIT VEXU Core API
|
#include <translation2d.h>
Public Member Functions | |
constexpr | Translation2d () |
Translation2d (const double &x, const double &y) | |
Translation2d (const Eigen::Vector2d &vector) | |
Translation2d (const double &r, const Rotation2d &theta) | |
double | x () const |
void | setX (double x) |
double | y () const |
void | setY (double y) |
Rotation2d | theta () const |
Eigen::Vector2d | as_vector () const |
double | norm () const |
Translation2d | normalize () const |
double | distance (const Translation2d &other) const |
Translation2d | rotate_by (const Rotation2d &rotation) const |
Translation2d | rotate_around (const Translation2d &other, const Rotation2d &rotation) const |
Translation2d | operator+ (const Translation2d &other) const |
Translation2d | operator- (const Translation2d &other) const |
Translation2d | operator- () const |
Translation2d | operator* (const double &scalar) const |
Translation2d | operator/ (const double &scalar) const |
double | operator* (const Translation2d &other) const |
bool | operator== (const Translation2d &other) const |
Friends | |
std::ostream & | operator<< (std::ostream &os, const Translation2d &translation) |
Class representing a point in 2d space with x and y coordinates.
Assumes conventional cartesian coordinate system: Looking down at the coordinate plane, +X is right +Y is up +Theta is counterclockwise
|
inlineconstexpr |
Default Constructor for Translation2d
Translation2d::Translation2d | ( | const double & | x, |
const double & | y ) |
Constructs a Translation2d with the given x and y values.
x | The x component of the translation. |
y | The y component of the translation. |
Translation2d::Translation2d | ( | const Eigen::Vector2d & | vector | ) |
Constructs a Translation2d with the values from the given vector.
vector | The vector whose values will be used. |
Translation2d::Translation2d | ( | const double & | r, |
const Rotation2d & | theta ) |
Constructs a Translation2d given polar coordinates of the form (r, theta).
r | The radius (magnitude) of the vector. |
theta | The angle (direction) of the vector. |
Eigen::Vector2d Translation2d::as_vector | ( | ) | const |
Returns the vector as an Eigen::Vector2d.
double Translation2d::distance | ( | const Translation2d & | other | ) | const |
Returns the distance between two translations.
double Translation2d::norm | ( | ) | const |
Returns the norm/radius/magnitude/distance from origin.
Translation2d Translation2d::normalize | ( | ) | const |
returns a translation as if it were a vector with a magnitude of 1
Returns a translation so that it has a vector magnitude of 1
Translation2d Translation2d::operator* | ( | const double & | scalar | ) | const |
Returns this translation multiplied by a scalar.
[x] = [x] * [scalar] [y] = [y] * [scalar]
scalar | the scalar to multiply by. |
double Translation2d::operator* | ( | const Translation2d & | other | ) | const |
Returns the dot product of two translations.
[scalar] = [x][otherx] + [y][othery]
other | the other translation to find the dot product with. |
Translation2d Translation2d::operator+ | ( | const Translation2d & | other | ) | const |
Returns the sum of two translations.
[x] = [x] + [otherx]; [y] = [y] + [othery];
other | the other translation to add to this translation. |
Translation2d Translation2d::operator- | ( | ) | const |
Returns the inverse of this translation. Equivalent to flipping the vector across the origin.
[x] = [-x] [y] = [-y]
Translation2d Translation2d::operator- | ( | const Translation2d & | other | ) | const |
Returns the difference of two translations.
[x] = [x] - [otherx] [y] = [y] - [othery]
other | the translation to subtract from this translation. |
Translation2d Translation2d::operator/ | ( | const double & | scalar | ) | const |
Returns this translation divided by a scalar.
[x] = [x] / [scalar] [y] = [y] / [scalar]
scalar | the scalar to divide by. |
bool Translation2d::operator== | ( | const Translation2d & | other | ) | const |
Compares two translations. Returns true if their components are each within 1e-9, to account for floating point error.
other | the translation to compare to. |
Translation2d Translation2d::rotate_around | ( | const Translation2d & | other, |
const Rotation2d & | rotation ) const |
Applies a rotation to this translation around another given point.
[x] = [cos, -sin][x - otherx] + [otherx] [y] = [sin, cos][y - othery] + [othery]
other | the center of rotation. |
rotation | the angle amount the translation will be rotated. |
Translation2d Translation2d::rotate_by | ( | const Rotation2d & | rotation | ) | const |
Applies a rotation to this translation around the origin.
Equivalent to multiplying a vector by a rotation matrix: x = [cos, -sin][x] y = [sin, cos][y]
rotation | the angle amount the translation will be rotated. |
void Translation2d::setX | ( | double | x | ) |
Sets the x value of the translation.
void Translation2d::setY | ( | double | y | ) |
Sets the y value of the translation.
Rotation2d Translation2d::theta | ( | ) | const |
Returns the angle of the translation.
double Translation2d::x | ( | ) | const |
Returns the x value of the translation.
double Translation2d::y | ( | ) | const |
Returns the y value of the translation.
|
friend |
Sends a translation to an output stream. Ex. std::cout << translation;
prints "Translation2d[x: (value), y: (value)]"
Sends a translation to an output stream. Ex. std::cout << translation;
prints "Translation2d[x: (value), y: (value), rad: (radians), deg: (degrees)]"