|
WPILibC++
2020.3.2
|
Represents a translation in 2d space. More...
#include <Translation2d.h>
Public Member Functions | |
| constexpr | Translation2d ()=default |
| Constructs a Translation2d with X and Y components equal to zero. | |
| Translation2d (units::meter_t x, units::meter_t y) | |
| Constructs a Translation2d with the X and Y components equal to the provided values. More... | |
| units::meter_t | Distance (const Translation2d &other) const |
| Calculates the distance between two translations in 2d space. More... | |
| units::meter_t | X () const |
| Returns the X component of the translation. More... | |
| units::meter_t | Y () const |
| Returns the Y component of the translation. More... | |
| units::meter_t | Norm () const |
| Returns the norm, or distance from the origin to the translation. More... | |
| Translation2d | RotateBy (const Rotation2d &other) const |
| Applies a rotation to the translation in 2d space. More... | |
| Translation2d | operator+ (const Translation2d &other) const |
| Adds two translations in 2d space and returns the sum. More... | |
| Translation2d & | operator+= (const Translation2d &other) |
| Adds the new translation to the current translation. More... | |
| Translation2d | operator- (const Translation2d &other) const |
| Subtracts the other translation from the other translation and returns the difference. More... | |
| Translation2d & | operator-= (const Translation2d &other) |
| Subtracts the new translation from the current translation. More... | |
| Translation2d | operator- () const |
| Returns the inverse of the current translation. More... | |
| Translation2d | operator* (double scalar) const |
| Multiplies the translation by a scalar and returns the new translation. More... | |
| Translation2d & | operator*= (double scalar) |
| Multiplies the current translation by a scalar. More... | |
| Translation2d | operator/ (double scalar) const |
| Divides the translation by a scalar and returns the new translation. More... | |
| bool | operator== (const Translation2d &other) const |
| Checks equality between this Translation2d and another object. More... | |
| bool | operator!= (const Translation2d &other) const |
| Checks inequality between this Translation2d and another object. More... | |
| Translation2d & | operator/= (double scalar) |
Represents a translation in 2d space.
This object can be used to represent a point or a vector.
This assumes that you are using conventional mathematical axes. When the robot is placed on the origin, facing toward the X direction, moving forward increases the X, whereas moving to the left increases the Y.
| frc::Translation2d::Translation2d | ( | units::meter_t | x, |
| units::meter_t | y | ||
| ) |
Constructs a Translation2d with the X and Y components equal to the provided values.
| x | The x component of the translation. |
| y | The y component of the translation. |
| units::meter_t frc::Translation2d::Distance | ( | const Translation2d & | other | ) | const |
Calculates the distance between two translations in 2d space.
This function uses the pythagorean theorem to calculate the distance. distance = std::sqrt((x2 - x1)^2 + (y2 - y1)^2)
| other | The translation to compute the distance to. |
| units::meter_t frc::Translation2d::Norm | ( | ) | const |
Returns the norm, or distance from the origin to the translation.
| bool frc::Translation2d::operator!= | ( | const Translation2d & | other | ) | const |
Checks inequality between this Translation2d and another object.
| other | The other object. |
| Translation2d frc::Translation2d::operator* | ( | double | scalar | ) | const |
Multiplies the translation by a scalar and returns the new translation.
For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}
| scalar | The scalar to multiply by. |
| Translation2d& frc::Translation2d::operator*= | ( | double | scalar | ) |
Multiplies the current translation by a scalar.
This is similar to the * operator, except that current object is mutated.
| scalar | The scalar to multiply by. |
| Translation2d frc::Translation2d::operator+ | ( | const Translation2d & | other | ) | const |
Adds two translations in 2d space and returns the sum.
This is similar to vector addition.
For example, Translation2d{1.0, 2.5} + Translation2d{2.0, 5.5} = Translation2d{3.0, 8.0}
| other | The translation to add. |
| Translation2d& frc::Translation2d::operator+= | ( | const Translation2d & | other | ) |
Adds the new translation to the current translation.
This is similar to the + operator, except that the current object is mutated.
| other | The translation to add. |
| Translation2d frc::Translation2d::operator- | ( | ) | const |
Returns the inverse of the current translation.
This is equivalent to rotating by 180 degrees, flipping the point over both axes, or simply negating both components of the translation.
| Translation2d frc::Translation2d::operator- | ( | const Translation2d & | other | ) | const |
Subtracts the other translation from the other translation and returns the difference.
For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} = Translation2d{4.0, 2.0}
| other | The translation to subtract. |
| Translation2d& frc::Translation2d::operator-= | ( | const Translation2d & | other | ) |
Subtracts the new translation from the current translation.
This is similar to the - operator, except that the current object is mutated.
| other | The translation to subtract. |
| Translation2d frc::Translation2d::operator/ | ( | double | scalar | ) | const |
Divides the translation by a scalar and returns the new translation.
For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}
| scalar | The scalar to divide by. |
| bool frc::Translation2d::operator== | ( | const Translation2d & | other | ) | const |
Checks equality between this Translation2d and another object.
| other | The other object. |
| Translation2d frc::Translation2d::RotateBy | ( | const Rotation2d & | other | ) | const |
Applies a rotation to the translation in 2d space.
This multiplies the translation vector by a counterclockwise rotation matrix of the given angle.
[x_new] [other.cos, -other.sin][x] [y_new] = [other.sin, other.cos][y]
For example, rotating a Translation2d of {2, 0} by 90 degrees will return a Translation2d of {0, 2}.
| other | The rotation to rotate the translation by. |
|
inline |
Returns the X component of the translation.
|
inline |
Returns the Y component of the translation.