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

#include <rotation2d.h>

Public Member Functions

constexpr Rotation2d ()
 
 Rotation2d (const double &radians)
 
 Rotation2d (const double &x, const double &y)
 
 Rotation2d (const Translation2d &translation)
 
double radians () const
 
double degrees () const
 
double revolutions () const
 
double f_cos () const
 
double f_sin () const
 
double f_tan () const
 
Eigen::Matrix2d rotation_matrix () const
 
double wrapped_radians_180 () const
 
double wrapped_degrees_180 () const
 
double wrapped_revolutions_180 () const
 
double wrapped_radians_360 () const
 
double wrapped_degrees_360 () const
 
double wrapped_revolutions_360 () const
 
Rotation2d operator+ (const Rotation2d &other) const
 
Rotation2d operator- (const Rotation2d &other) const
 
Rotation2d operator- () const
 
Rotation2d operator* (const double &scalar) const
 
Rotation2d operator/ (const double &scalar) const
 
bool operator== (const Rotation2d &other) const
 

Friends

std::ostream & operator<< (std::ostream &os, const Rotation2d &rotation)
 

Detailed Description

Class representing a rotation in 2d space. Stores theta in radians, as well as cos and sin.

Internally this angle is stored continuously, however there are functions that return wrapped angles: "180" is from [-pi, pi), [-180, 180), [-0.5, 0.5) "360" is from [0, 2pi), [0, 360), [0, 1)

Constructor & Destructor Documentation

◆ Rotation2d() [1/4]

Rotation2d::Rotation2d ( )
inlineconstexpr

Default Constructor for Rotation2d

◆ Rotation2d() [2/4]

Rotation2d::Rotation2d ( const double & radians)

Constructs a rotation with the given value in radians.

Parameters
radiansthe value of the rotation in radians.

◆ Rotation2d() [3/4]

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

Constructs a rotation given x and y values. Does not have to be normalized. The angle from the x axis to the point.

[theta] = [atan2(y, x)]

Parameters
xthe x value of the point
ythe y value of the point

◆ Rotation2d() [4/4]

Rotation2d::Rotation2d ( const Translation2d & translation)

Constructs a rotation given x and y values in the form of a Translation2d. Does not have to be normalized. The angle from the x axis to the point.

[theta] = [atan2(y, x)]

Parameters
translation

Member Function Documentation

◆ degrees()

double Rotation2d::degrees ( ) const

Returns the degree angle value.

Returns
the degree angle value.

◆ f_cos()

double Rotation2d::f_cos ( ) const

Returns the cosine of the angle value.

Returns
the cosine of the angle value

◆ f_sin()

double Rotation2d::f_sin ( ) const

Returns the sine of the angle value.

Returns
the sine of the angle value.

◆ f_tan()

double Rotation2d::f_tan ( ) const

Returns the tangent of the angle value.

Returns
the tangent of the angle value.

◆ operator*()

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

Multiplies this rotation by a scalar.

Parameters
scalarthe scalar value to multiply the rotation by.
Returns
the rotation multiplied by the scalar.

◆ operator+()

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

Adds the values of two rotations using a rotation matrix

[new_cos] = [other.cos, -other.sin][cos] [new_sin] = [other.sin, other.cos][sin] new_value = atan2(new_sin, new_cos)

Parameters
otherthe other rotation to add to this rotation.
Returns
the sum of the two rotations.

Adds the values of two rotations using a rotation matrix.

[new_cos] = [other.cos, -other.sin][cos] [new_sin] = [other.sin, other.cos][sin] new_value = atan2(new_sin, new_cos)

Parameters
otherthe other rotation to add to this rotation.
Returns
the sum of the two rotations.

◆ operator-() [1/2]

Rotation2d Rotation2d::operator- ( ) const

Takes the inverse of this rotation by flipping it. Equivalent to adding 180 degrees.

Returns
this inverse of the rotation.

Takes the inverse of this rotation by flipping it.

Returns
this inverse of the rotation.

◆ operator-() [2/2]

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

Subtracts the values of two rotations.

Parameters
otherthe other rotation to subtract from this rotation.
Returns
the difference between the two rotations.

◆ operator/()

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

Divides this rotation by a scalar.

Parameters
scalarthe scalar value to divide the rotation by.
Returns
the rotation divided by the scalar.

◆ operator==()

bool Rotation2d::operator== ( const Rotation2d & other) const

Compares two rotations. Returns true if their values are within 1e-9 radians of each other, to account for floating point error.

Parameters
otherthe other rotation to compare to
Returns
whether the values of the rotations are within 1e-9 radians of each other

◆ radians()

double Rotation2d::radians ( ) const

Returns the radian angle value.

Returns
the radian angle value.

◆ revolutions()

double Rotation2d::revolutions ( ) const

Returns the revolution angle value.

Returns
the revolution angle value.

◆ rotation_matrix()

Eigen::Matrix2d Rotation2d::rotation_matrix ( ) const

Returns the rotation matrix equivalent to this rotation [cos, -sin] R = [sin, cos]

Returns
the rotation matrix equivalent to this rotation

◆ wrapped_degrees_180()

double Rotation2d::wrapped_degrees_180 ( ) const

Returns the degree angle value, wrapped from [-180, 180).

Returns
the degree angle value, wrapped from [-180, 180)

◆ wrapped_degrees_360()

double Rotation2d::wrapped_degrees_360 ( ) const

Returns the degree angle value, wrapped from [0, 360).

Returns
the degree angle value, wrapped from [0, 360)

◆ wrapped_radians_180()

double Rotation2d::wrapped_radians_180 ( ) const

Returns the radian angle value, wrapped from [-pi, pi).

Returns
the radian angle value, wrapped from [-pi, pi)

◆ wrapped_radians_360()

double Rotation2d::wrapped_radians_360 ( ) const

Returns the radian angle value, wrapped from [0, 2pi).

Returns
the radian angle value, wrapped from [0, 2pi)

◆ wrapped_revolutions_180()

double Rotation2d::wrapped_revolutions_180 ( ) const

Returns the revolution angle value, wrapped from [-0.5, 0.5).

Returns
the revolution angle value, wrapped from [-0.5, 0.5)

◆ wrapped_revolutions_360()

double Rotation2d::wrapped_revolutions_360 ( ) const

Returns the revolution angle value, wrapped from [0, 1).

Returns
the revolution angle value, wrapped from [0, 1)

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream & os,
const Rotation2d & rotation )
friend

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

prints "Rotation2d[rad: (radians), deg: (degrees)]"


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