Class Translation3d
- All Implemented Interfaces:
Interpolatable<Translation3d>
,ProtobufSerializable
,StructSerializable
,WPISerializable
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, left is positive Y, and up is positive Z.
-
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final Translation3d
A preallocated Translation3d representing the origin.static final Translation3dProto
Translation3d protobuf for serialization.static final Translation3dStruct
Translation3d struct for serialization. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs a Translation3d with X, Y, and Z components equal to zero.Translation3d
(double x, double y, double z) Constructs a Translation3d with the X, Y, and Z components equal to the provided values.Translation3d
(double distance, Rotation3d angle) Constructs a Translation3d with the provided distance and angle.Translation3d
(Translation2d translation) Constructs a 3D translation from a 2D translation in the X-Y plane.Translation3d
(Vector<N3> vector) Constructs a Translation3d from a 3D translation vector.Translation3d
(Distance x, Distance y, Distance z) Constructs a Translation3d with the X, Y, and Z components equal to the provided values. -
Method Summary
Modifier and TypeMethodDescriptiondiv
(double scalar) Returns the translation divided by a scalar.boolean
Checks equality between this Translation3d and another object.double
getDistance
(Translation3d other) Calculates the distance between two translations in 3D space.Returns the X component of the translation in a measure.Returns the Y component of the translation in a measure.Returns the Z component of the translation in a measure.double
getNorm()
Returns the norm, or distance from the origin to the translation.double
getX()
Returns the X component of the translation.double
getY()
Returns the Y component of the translation.double
getZ()
Returns the Z component of the translation.int
hashCode()
interpolate
(Translation3d endValue, double t) Return the interpolated value.minus
(Translation3d other) Returns the difference between two translations.nearest
(Collection<Translation3d> translations) Returns the nearest Translation3d from a collection of translations.plus
(Translation3d other) Returns the sum of two translations in 3D space.rotateAround
(Translation3d other, Rotation3d rot) Rotates this translation around another translation in 3D space.rotateBy
(Rotation3d other) Applies a rotation to the translation in 3D space.times
(double scalar) Returns the translation multiplied by a scalar.toString()
Returns a Translation2d representing this Translation3d projected into the X-Y plane.toVector()
Returns a 2D translation vector representation of this translation.Returns the inverse of the current translation.
-
Field Details
-
kZero
A preallocated Translation3d representing the origin.This exists to avoid allocations for common translations.
-
proto
Translation3d protobuf for serialization. -
struct
Translation3d struct for serialization.
-
-
Constructor Details
-
Translation3d
public Translation3d()Constructs a Translation3d with X, Y, and Z components equal to zero. -
Translation3d
Constructs a Translation3d with the X, Y, and Z components equal to the provided values.- Parameters:
x
- The x component of the translation.y
- The y component of the translation.z
- The z component of the translation.
-
Translation3d
Constructs a Translation3d with the provided distance and angle. This is essentially converting from polar coordinates to Cartesian coordinates.- Parameters:
distance
- The distance from the origin to the end of the translation.angle
- The angle between the x-axis and the translation vector.
-
Translation3d
Constructs a Translation3d with the X, Y, and Z components equal to the provided values. The components will be converted to and tracked as meters.- Parameters:
x
- The x component of the translation.y
- The y component of the translation.z
- The z component of the translation.
-
Translation3d
Constructs a 3D translation from a 2D translation in the X-Y plane.- Parameters:
translation
- The 2D translation.- See Also:
-
Translation3d
Constructs a Translation3d from a 3D translation vector. The values are assumed to be in meters.- Parameters:
vector
- The translation vector.
-
-
Method Details
-
getDistance
Calculates the distance between two translations in 3D space.The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
- Parameters:
other
- The translation to compute the distance to.- Returns:
- The distance between the two translations.
-
getX
Returns the X component of the translation.- Returns:
- The X component of the translation.
-
getY
Returns the Y component of the translation.- Returns:
- The Y component of the translation.
-
getZ
Returns the Z component of the translation.- Returns:
- The Z component of the translation.
-
getMeasureX
Returns the X component of the translation in a measure.- Returns:
- The x component of the translation in a measure.
-
getMeasureY
Returns the Y component of the translation in a measure.- Returns:
- The y component of the translation in a measure.
-
getMeasureZ
Returns the Z component of the translation in a measure.- Returns:
- The z component of the translation in a measure.
-
toVector
Returns a 2D translation vector representation of this translation.- Returns:
- A 2D translation vector representation of this translation.
-
getNorm
Returns the norm, or distance from the origin to the translation.- Returns:
- The norm of the translation.
-
rotateBy
Applies a rotation to the translation in 3D space.For example, rotating a Translation3d of <2, 0, 0> by 90 degrees around the Z axis will return a Translation3d of <0, 2, 0>.
- Parameters:
other
- The rotation to rotate the translation by.- Returns:
- The new rotated translation.
-
rotateAround
Rotates this translation around another translation in 3D space.- Parameters:
other
- The other translation to rotate around.rot
- The rotation to rotate the translation by.- Returns:
- The new rotated translation.
-
toTranslation2d
Returns a Translation2d representing this Translation3d projected into the X-Y plane.- Returns:
- A Translation2d representing this Translation3d projected into the X-Y plane.
-
plus
Returns the sum of two translations in 3D space.For example, Translation3d(1.0, 2.5, 3.5) + Translation3d(2.0, 5.5, 7.5) = Translation3d{3.0, 8.0, 11.0).
- Parameters:
other
- The translation to add.- Returns:
- The sum of the translations.
-
minus
Returns the difference between two translations.For example, Translation3d(5.0, 4.0, 3.0) - Translation3d(1.0, 2.0, 3.0) = Translation3d(4.0, 2.0, 0.0).
- Parameters:
other
- The translation to subtract.- Returns:
- The difference between the two translations.
-
unaryMinus
Returns the inverse of the current translation. This is equivalent to negating all components of the translation.- Returns:
- The inverse of the current translation.
-
times
Returns the translation multiplied by a scalar.For example, Translation3d(2.0, 2.5, 4.5) * 2 = Translation3d(4.0, 5.0, 9.0).
- Parameters:
scalar
- The scalar to multiply by.- Returns:
- The scaled translation.
-
div
Returns the translation divided by a scalar.For example, Translation3d(2.0, 2.5, 4.5) / 2 = Translation3d(1.0, 1.25, 2.25).
- Parameters:
scalar
- The scalar to multiply by.- Returns:
- The reference to the new mutated object.
-
nearest
Returns the nearest Translation3d from a collection of translations.- Parameters:
translations
- The collection of translations to find the nearest.- Returns:
- The nearest Translation3d from the collection.
-
toString
-
equals
Checks equality between this Translation3d and another object. -
hashCode
-
interpolate
Description copied from interface:Interpolatable
Return the interpolated value. This object is assumed to be the starting position, or lower bound.- Specified by:
interpolate
in interfaceInterpolatable<Translation3d>
- Parameters:
endValue
- The upper bound, or end.t
- How far between the lower and upper bound we are. This should be bounded in [0, 1].- Returns:
- The interpolated value.
-