45 Pose3d(units::meter_t x, units::meter_t y, units::meter_t z,
92 units::meter_t
X()
const {
return m_translation.X(); }
99 units::meter_t
Y()
const {
return m_translation.Y(); }
106 units::meter_t
Z()
const {
return m_translation.Z(); }
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Represents a 3D pose containing translational and rotational elements.
Definition: Pose3d.h:21
Pose3d RelativeTo(const Pose3d &other) const
Returns the current pose relative to the given pose.
Pose2d ToPose2d() const
Returns a Pose2d representing this Pose3d projected into the X-Y plane.
Pose3d TransformBy(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Pose3d RotateBy(const Rotation3d &other) const
Rotates the pose around the origin and returns the new pose.
units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition: Pose3d.h:99
const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition: Pose3d.h:113
Twist3d Log(const Pose3d &end) const
Returns a Twist3d that maps this pose to the end pose.
Pose3d(Translation3d translation, Rotation3d rotation)
Constructs a pose with the specified translation and rotation.
Pose3d Exp(const Twist3d &twist) const
Obtain a new Pose3d from a (constant curvature) velocity.
units::meter_t X() const
Returns the X component of the pose's translation.
Definition: Pose3d.h:92
const Translation3d & Translation() const
Returns the underlying translation.
Definition: Pose3d.h:85
Pose3d operator+(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Pose3d operator*(double scalar) const
Multiplies the current pose by a scalar.
bool operator==(const Pose3d &) const =default
Checks equality between this Pose3d and another object.
Pose3d(const Pose2d &pose)
Constructs a 3D pose from a 2D pose in the X-Y plane.
Pose3d operator/(double scalar) const
Divides the current pose by a scalar.
units::meter_t Z() const
Returns the Z component of the pose's translation.
Definition: Pose3d.h:106
Transform3d operator-(const Pose3d &other) const
Returns the Transform3d that maps the one pose to another.
Pose3d(units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation)
Constructs a pose with x, y, and z translations instead of a separate Translation3d.
constexpr Pose3d()=default
Constructs a pose at the origin facing toward the positive X axis.
A rotation in a 3D coordinate frame represented by a quaternion.
Definition: Rotation3d.h:20
Represents a translation in 3D space.
Definition: Translation3d.h:25
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
A change in distance along a 3D arc since the last pose update.
Definition: Twist3d.h:22