Transform2d
- class wpimath.geometry.Transform2d(*args, **kwargs)
Bases:
pybind11_object
Represents a transformation for a Pose2d.
Overloaded function.
__init__(self: wpimath.geometry._geometry.Transform2d, initial: wpimath.geometry._geometry.Pose2d, final: wpimath.geometry._geometry.Pose2d) -> None
Constructs the transform that maps the initial pose to the final pose.
- Parameters:
initial – The initial pose for the transformation.
final – The final pose for the transformation.
__init__(self: wpimath.geometry._geometry.Transform2d, translation: wpimath.geometry._geometry.Translation2d, rotation: wpimath.geometry._geometry.Rotation2d) -> None
Constructs a transform with the given translation and rotation components.
- Parameters:
translation – Translational component of the transform.
rotation – Rotational component of the transform.
__init__(self: wpimath.geometry._geometry.Transform2d) -> None
Constructs the identity transform – maps an initial pose to itself.
__init__(self: wpimath.geometry._geometry.Transform2d, x: meters, y: meters, angle: radians) -> None
- X() meters
Returns the X component of the transformation’s translation.
- Returns:
The x component of the transformation’s translation.
- Y() meters
Returns the Y component of the transformation’s translation.
- Returns:
The y component of the transformation’s translation.
- static fromFeet(x: feet, y: feet, angle: radians) wpimath.geometry._geometry.Transform2d
- inverse() wpimath.geometry._geometry.Transform2d
Invert the transformation. This is useful for undoing a transformation.
- Returns:
The inverted transformation.
- rotation() wpimath.geometry._geometry.Rotation2d
Returns the rotational component of the transformation.
- Returns:
Reference to the rotational component of the transform.
- translation() wpimath.geometry._geometry.Translation2d
Returns the translation component of the transformation.
- Returns:
Reference to the translational component of the transform.
- property x
- property x_feet
- property y
- property y_feet