Package edu.wpi.first.math.geometry
Class Transform2d
java.lang.Object
edu.wpi.first.math.geometry.Transform2d
- All Implemented Interfaces:
ProtobufSerializable
,StructSerializable
,WPISerializable
Represents a transformation for a Pose2d in the pose's frame.
-
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final Transform2d
A preallocated Transform2d representing no transformation.static final Transform2dProto
Transform2d protobuf for serialization.static final Transform2dStruct
Transform2d struct for serialization. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs the identity transform -- maps an initial pose to itself.Transform2d
(double x, double y, Rotation2d rotation) Constructs a transform with x and y translations instead of a separate Translation2d.Transform2d
(Pose2d initial, Pose2d last) Constructs the transform that maps the initial pose to the final pose.Transform2d
(Translation2d translation, Rotation2d rotation) Constructs a transform with the given translation and rotation components.Transform2d
(Measure<Distance> x, Measure<Distance> y, Rotation2d rotation) Constructs a transform with x and y translations instead of a separate Translation2d. -
Method Summary
Modifier and TypeMethodDescriptiondiv
(double scalar) Divides the transform by the scalar.boolean
Checks equality between this Transform2d and another object.Returns the rotational component of the transformation.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.int
hashCode()
inverse()
Invert the transformation.plus
(Transform2d other) Composes two transformations.times
(double scalar) Multiplies the transform by the scalar.toString()
-
Field Details
-
kZero
A preallocated Transform2d representing no transformation.This exists to avoid allocations for common transformations.
-
proto
Transform2d protobuf for serialization. -
struct
Transform2d struct for serialization.
-
-
Constructor Details
-
Transform2d
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.
-
Transform2d
Constructs a transform with the given translation and rotation components.- Parameters:
translation
- Translational component of the transform.rotation
- Rotational component of the transform.
-
Transform2d
Constructs a transform with x and y translations instead of a separate Translation2d.- Parameters:
x
- The x component of the translational component of the transform.y
- The y component of the translational component of the transform.rotation
- The rotational component of the transform.
-
Transform2d
Constructs a transform with x and y translations instead of a separate Translation2d. The X and Y 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.rotation
- The rotational component of the transform.
-
Transform2d
public Transform2d()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 Transform2d.
-
div
Divides the transform by the scalar.- Parameters:
scalar
- The scalar.- Returns:
- The scaled Transform2d.
-
plus
Composes 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.
-
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.
-
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 Transform2d and another object. -
hashCode
-