48 Rotation3d(units::radian_t roll, units::radian_t pitch, units::radian_t yaw);
57 Rotation3d(
const Eigen::Vector3d& axis, units::radian_t angle);
74 explicit Rotation3d(
const Eigen::Matrix3d& rotationMatrix);
86 Rotation3d(
const Eigen::Vector3d& initial,
const Eigen::Vector3d&
final);
158 units::radian_t
X()
const;
163 units::radian_t
Y()
const;
168 units::radian_t
Z()
const;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a quaternion.
Definition: Quaternion.h:16
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
A rotation in a 3D coordinate frame represented by a quaternion.
Definition: Rotation3d.h:20
Rotation2d ToRotation2d() const
Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
Rotation3d operator-() const
Takes the inverse of the current rotation.
Rotation3d(units::radian_t roll, units::radian_t pitch, units::radian_t yaw)
Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
Rotation3d operator+(const Rotation3d &other) const
Adds two rotations together.
Rotation3d operator-(const Rotation3d &other) const
Subtracts the new rotation from the current rotation and returns the new rotation.
units::radian_t Y() const
Returns the counterclockwise rotation angle around the Y axis (pitch).
Rotation3d(const Eigen::Vector3d &rvec)
Constructs a Rotation3d with the given rotation vector representation.
Rotation3d operator/(double scalar) const
Divides the current rotation by a scalar.
Rotation3d(const Eigen::Vector3d &initial, const Eigen::Vector3d &final)
Constructs a Rotation3d that rotates the initial vector onto the final vector.
units::radian_t X() const
Returns the counterclockwise rotation angle around the X axis (roll).
units::radian_t Z() const
Returns the counterclockwise rotation angle around the Z axis (yaw).
Rotation3d(const Eigen::Matrix3d &rotationMatrix)
Constructs a Rotation3d from a rotation matrix.
Rotation3d(const Eigen::Vector3d &axis, units::radian_t angle)
Constructs a Rotation3d with the given axis-angle representation.
bool operator==(const Rotation3d &) const
Checks equality between this Rotation3d and another object.
units::radian_t Angle() const
Returns the angle in the axis-angle representation of this rotation.
Eigen::Vector3d Axis() const
Returns the axis in the axis-angle representation of this rotation.
Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Rotation3d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Rotation3d(const Quaternion &q)
Constructs a Rotation3d from a quaternion.
const Quaternion & GetQuaternion() const
Returns the quaternion representation of the Rotation3d.
Rotation3d()=default
Constructs a Rotation3d with a default angle of 0 degrees.
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