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

#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)
 

Detailed Description

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

Constructor & Destructor Documentation

◆ Translation2d() [1/4]

Translation2d::Translation2d ( )
inlineconstexpr

Default Constructor for Translation2d

◆ Translation2d() [2/4]

Translation2d::Translation2d ( const double & x,
const double & y )

Constructs a Translation2d with the given x and y values.

Parameters
xThe x component of the translation.
yThe y component of the translation.

◆ Translation2d() [3/4]

Translation2d::Translation2d ( const Eigen::Vector2d & vector)

Constructs a Translation2d with the values from the given vector.

Parameters
vectorThe vector whose values will be used.

◆ Translation2d() [4/4]

Translation2d::Translation2d ( const double & r,
const Rotation2d & theta )

Constructs a Translation2d given polar coordinates of the form (r, theta).

Parameters
rThe radius (magnitude) of the vector.
thetaThe angle (direction) of the vector.

Member Function Documentation

◆ as_vector()

Eigen::Vector2d Translation2d::as_vector ( ) const

Returns the vector as an Eigen::Vector2d.

Returns
Eigen::Vector2d with the same values as the translation.

◆ distance()

double Translation2d::distance ( const Translation2d & other) const

Returns the distance between two translations.

Returns
the distance between two translations.

◆ norm()

double Translation2d::norm ( ) const

Returns the norm/radius/magnitude/distance from origin.

Returns
the norm of the translation.

◆ normalize()

Translation2d Translation2d::normalize ( ) const

returns a translation as if it were a vector with a magnitude of 1

Returns
the norm of the translation.

Returns a translation so that it has a vector magnitude of 1

Returns
the norm of the translation.

◆ operator*() [1/2]

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

Returns this translation multiplied by a scalar.

[x] = [x] * [scalar] [y] = [y] * [scalar]

Parameters
scalarthe scalar to multiply by.
Returns
this translation multiplied by a scalar.

◆ operator*() [2/2]

double Translation2d::operator* ( const Translation2d & other) const

Returns the dot product of two translations.

[scalar] = [x][otherx] + [y][othery]

Parameters
otherthe other translation to find the dot product with.
Returns
the scalar valued dot product.

◆ operator+()

Translation2d Translation2d::operator+ ( const Translation2d & other) const

Returns the sum of two translations.

[x] = [x] + [otherx]; [y] = [y] + [othery];

Parameters
otherthe other translation to add to this translation.
Returns
the sum of the two translations.

◆ operator-() [1/2]

Translation2d Translation2d::operator- ( ) const

Returns the inverse of this translation. Equivalent to flipping the vector across the origin.

[x] = [-x] [y] = [-y]

Returns
the inverse of this translation.

◆ operator-() [2/2]

Translation2d Translation2d::operator- ( const Translation2d & other) const

Returns the difference of two translations.

[x] = [x] - [otherx] [y] = [y] - [othery]

Parameters
otherthe translation to subtract from this translation.
Returns
the difference of the two translations.

◆ operator/()

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

Returns this translation divided by a scalar.

[x] = [x] / [scalar] [y] = [y] / [scalar]

Parameters
scalarthe scalar to divide by.
Returns
this translation divided by a scalar.

◆ operator==()

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.

Parameters
otherthe translation to compare to.
Returns
whether the two translations are equal.

◆ rotate_around()

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]

Parameters
otherthe center of rotation.
rotationthe angle amount the translation will be rotated.
Returns
the translation that has been rotated.

◆ rotate_by()

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]

Parameters
rotationthe angle amount the translation will be rotated.
Returns
the new translation that has been rotated around the origin.

◆ setX()

void Translation2d::setX ( double x)

Sets the x value of the translation.

◆ setY()

void Translation2d::setY ( double y)

Sets the y value of the translation.

◆ theta()

Rotation2d Translation2d::theta ( ) const

Returns the angle of the translation.

Returns
the angle of the translation.

◆ x()

double Translation2d::x ( ) const

Returns the x value of the translation.

Returns
the x value of the translation.

◆ y()

double Translation2d::y ( ) const

Returns the y value of the translation.

Returns
the y value of the translation.

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream & os,
const Translation2d & 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)]"


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