Package edu.wpi.first.math.geometry
Class Transform3d
java.lang.Object
edu.wpi.first.math.geometry.Transform3d
- All Implemented Interfaces:
- ProtobufSerializable,- StructSerializable,- WPISerializable
Represents a transformation for a Pose3d in the pose's frame.
- 
Field SummaryFieldsModifier and TypeFieldDescriptionstatic final Transform3dA preallocated Transform3d representing no transformation.static final Transform3dProtoTransform3d protobuf for serialization.static final Transform3dStructTransform3d struct for serialization.
- 
Constructor SummaryConstructorsConstructorDescriptionConstructs the identity transform -- maps an initial pose to itself.Transform3d(double x, double y, double z, Rotation3d rotation) Constructs a transform with x, y, and z translations instead of a separate Translation3d.Transform3d(Pose3d initial, Pose3d last) Constructs the transform that maps the initial pose to the final pose.Transform3d(Transform2d transform) Constructs a 3D transform from a 2D transform in the X-Y plane.Transform3d(Translation3d translation, Rotation3d rotation) Constructs a transform with the given translation and rotation components.Transform3d(Matrix<N4, N4> matrix) Constructs a transform with the specified affine transformation matrix.Transform3d(Distance x, Distance y, Distance z, Rotation3d rotation) Constructs a transform with x, y, and z translations instead of a separate Translation3d.
- 
Method SummaryModifier and TypeMethodDescriptiondiv(double scalar) Divides the transform by the scalar.booleanChecks equality between this Transform3d and another object.Returns the X component of the transformation's translation in a measure.Returns the Y component of the transformation's translation in a measure.Returns the Z component of the transformation's translation in a measure.Returns the rotational component of the transformation.Returns the translation component of the transformation.doublegetX()Returns the X component of the transformation's translation.doublegetY()Returns the Y component of the transformation's translation.doublegetZ()Returns the Z component of the transformation's translation.inthashCode()inverse()Invert the transformation.plus(Transform3d other) Composes two transformations.times(double scalar) Multiplies the transform by the scalar.toMatrix()Returns an affine transformation matrix representation of this transformation.toString()
- 
Field Details- 
kZeroA preallocated Transform3d representing no transformation.This exists to avoid allocations for common transformations. 
- 
protoTransform3d protobuf for serialization.
- 
structTransform3d struct for serialization.
 
- 
- 
Constructor Details- 
Transform3dConstructs 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.
 
- 
Transform3dConstructs a transform with the given translation and rotation components.- Parameters:
- translation- Translational component of the transform.
- rotation- Rotational component of the transform.
 
- 
Transform3dConstructs a transform with x, y, and z translations instead of a separate Translation3d.- Parameters:
- x- The x component of the translational component of the transform.
- y- The y component of the translational component of the transform.
- z- The z component of the translational component of the transform.
- rotation- The rotational component of the transform.
 
- 
Transform3dConstructs a transform with x, y, and z translations instead of a separate Translation3d. The X, Y, and Z translations will be converted to and tracked as meters.- Parameters:
- x- The x component of the translational component of the transform.
- y- The y component of the translational component of the transform.
- z- The z component of the translational component of the transform.
- rotation- The rotational component of the transform.
 
- 
Transform3dConstructs a transform with the specified affine transformation matrix.- Parameters:
- matrix- The affine transformation matrix.
- Throws:
- IllegalArgumentException- if the affine transformation matrix is invalid.
 
- 
Transform3dpublic Transform3d()Constructs the identity transform -- maps an initial pose to itself.
- 
Transform3dConstructs a 3D transform from a 2D transform in the X-Y plane.- Parameters:
- transform- The 2D transform.
- See Also:
 
 
- 
- 
Method Details- 
timesMultiplies the transform by the scalar.- Parameters:
- scalar- The scalar.
- Returns:
- The scaled Transform3d.
 
- 
divDivides the transform by the scalar.- Parameters:
- scalar- The scalar.
- Returns:
- The scaled Transform3d.
 
- 
plusComposes two transformations. The second transform is applied relative to the orientation of the first.- Parameters:
- other- The transform to compose with this one.
- Returns:
- The composition of the two transformations.
 
- 
getTranslationReturns the translation component of the transformation.- Returns:
- The translational component of the transform.
 
- 
getXReturns the X component of the transformation's translation.- Returns:
- The x component of the transformation's translation.
 
- 
getYReturns the Y component of the transformation's translation.- Returns:
- The y component of the transformation's translation.
 
- 
getZReturns the Z component of the transformation's translation.- Returns:
- The z component of the transformation's translation.
 
- 
getMeasureXReturns the X component of the transformation's translation in a measure.- Returns:
- The x component of the transformation's translation in a measure.
 
- 
getMeasureYReturns the Y component of the transformation's translation in a measure.- Returns:
- The y component of the transformation's translation in a measure.
 
- 
getMeasureZReturns the Z component of the transformation's translation in a measure.- Returns:
- The z component of the transformation's translation in a measure.
 
- 
toMatrixReturns an affine transformation matrix representation of this transformation.- Returns:
- An affine transformation matrix representation of this transformation.
 
- 
getRotationReturns the rotational component of the transformation.- Returns:
- Reference to the rotational component of the transform.
 
- 
inverseInvert the transformation. This is useful for undoing a transformation.- Returns:
- The inverted transformation.
 
- 
toString
- 
equalsChecks equality between this Transform3d and another object.
- 
hashCode
 
-