Robot Core Documentation
|
Public Member Functions | |
Translation2d () | |
Translation2d ( @JsonProperty(required=true, value="x") double x, @JsonProperty(required=true, value="y") double y) | |
Translation2d (double distance, Rotation2d angle) | |
Translation2d (Measure< Distance > x, Measure< Distance > y) | |
double | getDistance (Translation2d other) |
double | getX () |
double | getY () |
double | getNorm () |
Rotation2d | getAngle () |
Translation2d | rotateBy (Rotation2d other) |
Translation2d | plus (Translation2d other) |
Translation2d | minus (Translation2d other) |
Translation2d | unaryMinus () |
Translation2d | times (double scalar) |
Translation2d | div (double scalar) |
Translation2d | nearest (List< Translation2d > translations) |
boolean | equals (Object obj) |
![]() | |
T | interpolate (T endValue, double t) |
Static Public Attributes | |
static final Translation2dProto | proto = new Translation2dProto() |
static final Translation2dStruct | struct = new Translation2dStruct() |
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 at the origin facing in the positive X direction, forward is positive X and left is positive Y.
edu.wpi.first.math.geometry.Translation2d.Translation2d | ( | ) |
Constructs a Translation2d with X and Y components equal to zero.
edu.wpi.first.math.geometry.Translation2d.Translation2d | ( | @JsonProperty(required=true, value="x") double | x, |
@JsonProperty(required=true, value="y") double | 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. |
edu.wpi.first.math.geometry.Translation2d.Translation2d | ( | double | distance, |
Rotation2d | angle ) |
Constructs a Translation2d with the provided distance and angle. This is essentially converting from polar coordinates to Cartesian coordinates.
distance | The distance from the origin to the end of the translation. |
angle | The angle between the x-axis and the translation vector. |
edu.wpi.first.math.geometry.Translation2d.Translation2d | ( | Measure< Distance > | x, |
Measure< Distance > | y ) |
Constructs a Translation2d with the X and Y components equal to the provided values. The X and Y components will be converted to and tracked as meters.
x | The x component of the translation. |
y | The y component of the translation. |
Translation2d edu.wpi.first.math.geometry.Translation2d.div | ( | double | scalar | ) |
Returns the translation divided by a scalar.
For example, Translation3d(2.0, 2.5) / 2 = Translation3d(1.0, 1.25).
scalar | The scalar to multiply by. |
boolean edu.wpi.first.math.geometry.Translation2d.equals | ( | Object | obj | ) |
Checks equality between this Translation2d and another object.
obj | The other object. |
Rotation2d edu.wpi.first.math.geometry.Translation2d.getAngle | ( | ) |
Returns the angle this translation forms with the positive X axis.
double edu.wpi.first.math.geometry.Translation2d.getDistance | ( | Translation2d | other | ) |
Calculates the distance between two translations in 2D space.
The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
other | The translation to compute the distance to. |
double edu.wpi.first.math.geometry.Translation2d.getNorm | ( | ) |
Returns the norm, or distance from the origin to the translation.
double edu.wpi.first.math.geometry.Translation2d.getX | ( | ) |
Returns the X component of the translation.
double edu.wpi.first.math.geometry.Translation2d.getY | ( | ) |
Returns the Y component of the translation.
Translation2d edu.wpi.first.math.geometry.Translation2d.minus | ( | Translation2d | other | ) |
Returns the difference between two translations.
For example, Translation2d(5.0, 4.0) - Translation2d(1.0, 2.0) = Translation2d(4.0, 2.0).
other | The translation to subtract. |
Translation2d edu.wpi.first.math.geometry.Translation2d.nearest | ( | List< Translation2d > | translations | ) |
Returns the nearest Translation2d from a list of translations.
translations | The list of translations. |
Translation2d edu.wpi.first.math.geometry.Translation2d.plus | ( | Translation2d | other | ) |
Returns the sum of two translations in 2D space.
For example, Translation3d(1.0, 2.5) + Translation3d(2.0, 5.5) = Translation3d{3.0, 8.0).
other | The translation to add. |
Translation2d edu.wpi.first.math.geometry.Translation2d.rotateBy | ( | Rotation2d | other | ) |
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. |
Translation2d edu.wpi.first.math.geometry.Translation2d.times | ( | double | scalar | ) |
Returns the translation multiplied by a scalar.
For example, Translation2d(2.0, 2.5) * 2 = Translation2d(4.0, 5.0).
scalar | The scalar to multiply by. |
Translation2d edu.wpi.first.math.geometry.Translation2d.unaryMinus | ( | ) |
Returns the inverse of the current translation. This is equivalent to rotating by 180 degrees, flipping the point over both axes, or negating all components of the translation.
|
static |
Translation2d protobuf for serialization.
|
static |
Translation2d struct for serialization.