183 Eigen::Vector3d m_v{0.0, 0.0, 0.0};
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a quaternion.
Definition: Quaternion.h:16
Quaternion()=default
Constructs a quaternion with a default angle of 0 degrees.
Quaternion operator*(const double other) const
Multiples with a scalar value.
bool operator==(const Quaternion &other) const
Checks equality between this Quaternion and another object.
Quaternion operator-(const Quaternion &other) const
Subtracts another quaternion.
double W() const
Returns W component of the quaternion.
Quaternion Exp() const
Matrix exponential of a quaternion.
Quaternion Exp(const Quaternion &other) const
Matrix exponential of a quaternion.
Eigen::Vector3d ToRotationVector() const
Returns the rotation vector representation of this quaternion.
Quaternion Normalize() const
Normalizes the quaternion.
Quaternion operator*(const Quaternion &other) const
Multiply with another quaternion.
double Norm() const
Calculates the L2 norm of the quaternion.
Quaternion operator+(const Quaternion &other) const
Adds with another quaternion.
double Dot(const Quaternion &other) const
Returns the elementwise product of two quaternions.
Quaternion Inverse() const
Returns the inverse of the quaternion.
double Z() const
Returns Z component of the quaternion.
double X() const
Returns X component of the quaternion.
Quaternion Pow(const double t) const
Calculates this quaternion raised to a power.
Quaternion Log() const
Log operator of a quaternion.
double Y() const
Returns Y component of the quaternion.
Quaternion Log(const Quaternion &other) const
Log operator of a quaternion.
Quaternion operator/(const double other) const
Divides by a scalar value.
static Quaternion FromRotationVector(const Eigen::Vector3d &rvec)
Returns the quaternion representation of this rotation vector.
Quaternion(double w, double x, double y, double z)
Constructs a quaternion with the given components.
Quaternion Conjugate() const
Returns the conjugate of the quaternion.
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)