Transform3d
- class wpimath.geometry.Transform3d(*args, **kwargs)
Bases:
pybind11_object
Represents a transformation for a Pose3d in the pose’s frame.
Overloaded function.
__init__(self: wpimath.geometry._geometry.Transform3d, initial: wpimath.geometry._geometry.Pose3d, final: wpimath.geometry._geometry.Pose3d) -> 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.Transform3d, translation: wpimath.geometry._geometry.Translation3d, rotation: wpimath.geometry._geometry.Rotation3d) -> 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.Transform3d, x: wpimath.units.meters, y: wpimath.units.meters, z: wpimath.units.meters, rotation: wpimath.geometry._geometry.Rotation3d) -> None
Constructs 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.
__init__(self: wpimath.geometry._geometry.Transform3d) -> None
Constructs the identity transform – maps an initial pose to itself.
- WPIStruct = <capsule object "WPyStruct">
- X() wpimath.units.meters
Returns the X component of the transformation’s translation.
- Returns:
The x component of the transformation’s translation.
- Y() wpimath.units.meters
Returns the Y component of the transformation’s translation.
- Returns:
The y component of the transformation’s translation.
- Z() wpimath.units.meters
Returns the Z component of the transformation’s translation.
- Returns:
The z component of the transformation’s translation.
- inverse() wpimath.geometry._geometry.Transform3d
Invert the transformation. This is useful for undoing a transformation.
- Returns:
The inverted transformation.
- rotation() wpimath.geometry._geometry.Rotation3d
Returns the rotational component of the transformation.
- Returns:
Reference to the rotational component of the transform.
- translation() wpimath.geometry._geometry.Translation3d
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
- property z
- property z_feet