Translation3d
- class wpimath.geometry.Translation3d(*args, **kwargs)
Bases:
pybind11_object
Represents a translation in 3D space. This object can be used to represent a point or a vector.
This assumes that you are using conventional mathematical axes. When the robot is at the origin facing in the positive X direction, forward is positive X, left is positive Y, and up is positive Z.
Overloaded function.
__init__(self: wpimath.geometry._geometry.Translation3d) -> None
Constructs a Translation3d with X, Y, and Z components equal to zero.
__init__(self: wpimath.geometry._geometry.Translation3d, x: meters, y: meters, z: meters) -> None
Constructs a Translation3d with the X, Y, and Z components equal to the provided values.
- Parameters:
x – The x component of the translation.
y – The y component of the translation.
z – The z component of the translation.
__init__(self: wpimath.geometry._geometry.Translation3d, distance: meters, angle: wpimath.geometry._geometry.Rotation3d) -> None
Constructs a Translation3d with the provided distance and angle. This is essentially converting from polar coordinates to Cartesian coordinates.
- Parameters:
distance – The distance from the origin to the end of the translation.
angle – The angle between the x-axis and the translation vector.
- X() meters
Returns the X component of the translation.
- Returns:
The Z component of the translation.
- Y() meters
Returns the Y component of the translation.
- Returns:
The Y component of the translation.
- Z() meters
Returns the Z component of the translation.
- Returns:
The Z component of the translation.
- distance(other: wpimath.geometry._geometry.Translation3d) meters
Calculates the distance between two translations in 3D space.
The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
- Parameters:
other – The translation to compute the distance to.
- Returns:
The distance between the two translations.
- distanceFeet(arg0: wpimath.geometry._geometry.Translation3d) feet
- static fromFeet(x: feet, y: feet, z: feet) wpimath.geometry._geometry.Translation3d
- norm() meters
Returns the norm, or distance from the origin to the translation.
- Returns:
The norm of the translation.
- normFeet() feet
- rotateBy(other: wpimath.geometry._geometry.Rotation3d) wpimath.geometry._geometry.Translation3d
Applies a rotation to the translation in 3D space.
For example, rotating a Translation3d of <2, 0, 0> by 90 degrees around the Z axis will return a Translation3d of <0, 2, 0>.
- Parameters:
other – The rotation to rotate the translation by.
- Returns:
The new rotated translation.
- toTranslation2d() wpimath.geometry._geometry.Translation2d
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
- property x
- property x_feet
- property y
- property y_feet
- property z
- property z_feet