Package edu.wpi.first.math.geometry
Class Transform3d
java.lang.Object
edu.wpi.first.math.geometry.Transform3d
public class Transform3d extends Object
Represents a transformation for a Pose3d.
-
Constructor Summary
Constructors Constructor Description Transform3d()
Constructs the identity transform -- maps an initial pose to itself.Transform3d(Pose3d initial, Pose3d last)
Constructs the transform that maps the initial pose to the final pose.Transform3d(Translation3d translation, Rotation3d rotation)
Constructs a transform with the given translation and rotation components. -
Method Summary
Modifier and Type Method Description Transform3d
div(double scalar)
Divides the transform by the scalar.boolean
equals(Object obj)
Checks equality between this Transform3d and another object.Rotation3d
getRotation()
Returns the rotational component of the transformation.Translation3d
getTranslation()
Returns the translation component of the transformation.double
getX()
Returns the X component of the transformation's translation.double
getY()
Returns the Y component of the transformation's translation.double
getZ()
Returns the Z component of the transformation's translation.int
hashCode()
Transform3d
inverse()
Invert the transformation.Transform3d
plus(Transform3d other)
Composes two transformations.Transform3d
times(double scalar)
Multiplies the transform by the scalar.String
toString()
-
Constructor Details
-
Transform3d
Constructs the transform that maps the initial pose to the final pose.- Parameters:
initial
- The initial pose for the transformation.last
- The final pose for the transformation.
-
Transform3d
Constructs a transform with the given translation and rotation components.- Parameters:
translation
- Translational component of the transform.rotation
- Rotational component of the transform.
-
Transform3d
public Transform3d()Constructs the identity transform -- maps an initial pose to itself.
-
-
Method Details
-
times
Multiplies the transform by the scalar.- Parameters:
scalar
- The scalar.- Returns:
- The scaled Transform3d.
-
div
Divides the transform by the scalar.- Parameters:
scalar
- The scalar.- Returns:
- The scaled Transform3d.
-
plus
Composes two transformations.- Parameters:
other
- The transform to compose with this one.- Returns:
- The composition of the two transformations.
-
getTranslation
Returns the translation component of the transformation.- Returns:
- The translational component of the transform.
-
getX
Returns the X component of the transformation's translation.- Returns:
- The x component of the transformation's translation.
-
getY
Returns the Y component of the transformation's translation.- Returns:
- The y component of the transformation's translation.
-
getZ
Returns the Z component of the transformation's translation.- Returns:
- The z component of the transformation's translation.
-
getRotation
Returns the rotational component of the transformation.- Returns:
- Reference to the rotational component of the transform.
-
inverse
Invert the transformation. This is useful for undoing a transformation.- Returns:
- The inverted transformation.
-
toString
-
equals
Checks equality between this Transform3d and another object. -
hashCode
-