Pose3d

class wpimath.geometry.Pose3d(*args, **kwargs)

Bases: pybind11_object

Represents a 3D pose containing translational and rotational elements.

Overloaded function.

  1. __init__(self: wpimath.geometry._geometry.Pose3d) -> None

Constructs a pose at the origin facing toward the positive X axis.

  1. __init__(self: wpimath.geometry._geometry.Pose3d, translation: wpimath.geometry._geometry.Translation3d, rotation: wpimath.geometry._geometry.Rotation3d) -> None

Constructs a pose with the specified translation and rotation.

Parameters:
  • translation – The translational component of the pose.

  • rotation – The rotational component of the pose.

  1. __init__(self: wpimath.geometry._geometry.Pose3d, x: meters, y: meters, z: meters, rotation: wpimath.geometry._geometry.Rotation3d) -> None

Constructs a pose with x, y, and z translations instead of a separate Translation3d.

Parameters:
  • x – The x component of the translational component of the pose.

  • y – The y component of the translational component of the pose.

  • z – The z component of the translational component of the pose.

  • rotation – The rotational component of the pose.

  1. __init__(self: wpimath.geometry._geometry.Pose3d, pose: wpimath.geometry._geometry.Pose2d) -> None

Constructs a 3D pose from a 2D pose in the X-Y plane.

Parameters:

pose – The 2D pose.

X() meters

Returns the X component of the pose’s translation.

Returns:

The x component of the pose’s translation.

Y() meters

Returns the Y component of the pose’s translation.

Returns:

The y component of the pose’s translation.

Z() meters

Returns the Z component of the pose’s translation.

Returns:

The z component of the pose’s translation.

exp(twist: wpimath.geometry._geometry.Twist3d) wpimath.geometry._geometry.Pose3d

Obtain a new Pose3d from a (constant curvature) velocity.

The twist is a change in pose in the robot’s coordinate frame since the previous pose update. When the user runs exp() on the previous known field-relative pose with the argument being the twist, the user will receive the new field-relative pose.

“Exp” represents the pose exponential, which is solving a differential equation moving the pose forward in time.

Parameters:

twist – The change in pose in the robot’s coordinate frame since the previous pose update. For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5 degrees since the previous pose update, the twist would be Twist3d{0.01_m, 0_m, 0_m, Rotation3d{0.0, 0.0, 0.5_deg}}.

Returns:

The new pose of the robot.

static fromFeet(x: feet, y: feet, z: feet, r: wpimath.geometry._geometry.Rotation3d) wpimath.geometry._geometry.Pose3d
log(end: wpimath.geometry._geometry.Pose3d) wpimath.geometry._geometry.Twist3d

Returns a Twist3d that maps this pose to the end pose. If c is the output of a.Log(b), then a.Exp(c) would yield b.

Parameters:

end – The end pose for the transformation.

Returns:

The twist that maps this to end.

relativeTo(other: wpimath.geometry._geometry.Pose3d) wpimath.geometry._geometry.Pose3d

Returns the current pose relative to the given pose.

This function can often be used for trajectory tracking or pose stabilization algorithms to get the error between the reference and the current pose.

Parameters:

other – The pose that is the origin of the new coordinate frame that the current pose will be converted into.

Returns:

The current pose relative to the new origin pose.

rotation() wpimath.geometry._geometry.Rotation3d

Returns the underlying rotation.

Returns:

Reference to the rotational component of the pose.

toPose2d() wpimath.geometry._geometry.Pose2d

Returns a Pose2d representing this Pose3d projected into the X-Y plane.

transformBy(other: wpimath.geometry._geometry.Transform3d) wpimath.geometry._geometry.Pose3d

Transforms the pose by the given transformation and returns the new pose. See + operator for the matrix multiplication performed.

Parameters:

other – The transform to transform the pose by.

Returns:

The transformed pose.

translation() wpimath.geometry._geometry.Translation3d

Returns the underlying translation.

Returns:

Reference to the translational component of the pose.

property x
property x_feet
property y
property y_feet
property z
property z_feet