public class RigidTransform2d extends java.lang.Object implements Interpolable<RigidTransform2d>
Modifier and Type | Class and Description |
---|---|
static class |
RigidTransform2d.Delta
Movement along an arc at constant curvature and velocity.
|
Modifier and Type | Field and Description |
---|---|
protected Rotation2d |
rotation_ |
protected Translation2d |
translation_ |
Constructor and Description |
---|
RigidTransform2d()
default rigidTransform has 0 rotation and translation
|
RigidTransform2d(RigidTransform2d other)
makes a copy of the given rigidTransform
|
RigidTransform2d(Translation2d translation,
Rotation2d rotation) |
Modifier and Type | Method and Description |
---|---|
static RigidTransform2d |
fromRotation(Rotation2d rotation)
generates a rigidTransform with the given rotation component and 0
translation
|
static RigidTransform2d |
fromTranslation(Translation2d translation)
generates a rigidTransform with the given translation component and 0
rotation
|
static RigidTransform2d |
fromVelocity(RigidTransform2d.Delta delta)
Obtain a new RigidTransform2d from a (constant curvature) velocity.
|
Rotation2d |
getRotation() |
Translation2d |
getTranslation() |
RigidTransform2d |
interpolate(RigidTransform2d other,
double x)
Do linear interpolation of this transform (there are more accurate ways
using constant curvature, but this is good enough).
|
RigidTransform2d |
inverse()
The inverse of this transform "undoes" the effect of translating by this
transform.
|
void |
setRotation(Rotation2d rotation) |
void |
setTranslation(Translation2d translation) |
java.lang.String |
toString() |
RigidTransform2d |
transformBy(RigidTransform2d other)
Transforming this RigidTransform2d means first translating by
other.translation and then rotating by other.rotation
|
protected Translation2d translation_
protected Rotation2d rotation_
public RigidTransform2d()
public RigidTransform2d(Translation2d translation, Rotation2d rotation)
translation
- the translation component of the transformrotation
- the rotation component of the transformpublic RigidTransform2d(RigidTransform2d other)
other
- the rigidTransform to copypublic static RigidTransform2d fromTranslation(Translation2d translation)
translation
- the translation componentpublic static RigidTransform2d fromRotation(Rotation2d rotation)
rotation
- the rotation componentpublic static RigidTransform2d fromVelocity(RigidTransform2d.Delta delta)
delta
- the velocity to watchpublic Translation2d getTranslation()
public void setTranslation(Translation2d translation)
translation
- the new translation componentpublic Rotation2d getRotation()
public void setRotation(Rotation2d rotation)
rotation
- the new rotation componentpublic RigidTransform2d transformBy(RigidTransform2d other)
other
- The other transform.public RigidTransform2d inverse()
public RigidTransform2d interpolate(RigidTransform2d other, double x)
interpolate
in interface Interpolable<RigidTransform2d>
other
- The value of the upper boundx
- The requested value. Should be between 0 and 1.public java.lang.String toString()
toString
in class java.lang.Object