WPILibC++ 2023.4.3-108-ge5452e3
Quaternion.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <wpi/SymbolExports.h>
8
9#include "frc/EigenCore.h"
10
11namespace wpi {
12class json;
13} // namespace wpi
14
15namespace frc {
16
18 public:
19 /**
20 * Constructs a quaternion with a default angle of 0 degrees.
21 */
22 Quaternion() = default;
23
24 /**
25 * Constructs a quaternion with the given components.
26 *
27 * @param w W component of the quaternion.
28 * @param x X component of the quaternion.
29 * @param y Y component of the quaternion.
30 * @param z Z component of the quaternion.
31 */
32 Quaternion(double w, double x, double y, double z);
33
34 /**
35 * Multiply with another quaternion.
36 *
37 * @param other The other quaternion.
38 */
39 Quaternion operator*(const Quaternion& other) const;
40
41 /**
42 * Checks equality between this Quaternion and another object.
43 *
44 * @param other The other object.
45 * @return Whether the two objects are equal.
46 */
47 bool operator==(const Quaternion& other) const;
48
49 /**
50 * Returns the inverse of the quaternion.
51 */
53
54 /**
55 * Normalizes the quaternion.
56 */
58
59 /**
60 * Returns W component of the quaternion.
61 */
62 double W() const;
63
64 /**
65 * Returns X component of the quaternion.
66 */
67 double X() const;
68
69 /**
70 * Returns Y component of the quaternion.
71 */
72 double Y() const;
73
74 /**
75 * Returns Z component of the quaternion.
76 */
77 double Z() const;
78
79 /**
80 * Returns the rotation vector representation of this quaternion.
81 *
82 * This is also the log operator of SO(3).
83 */
84 Eigen::Vector3d ToRotationVector() const;
85
86 private:
87 double m_r = 1.0;
88 Eigen::Vector3d m_v{0.0, 0.0, 0.0};
89};
90
92void to_json(wpi::json& json, const Quaternion& quaternion);
93
95void from_json(const wpi::json& json, Quaternion& quaternion);
96
97} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Definition: Quaternion.h:17
Quaternion()=default
Constructs a quaternion with a default angle of 0 degrees.
bool operator==(const Quaternion &other) const
Checks equality between this Quaternion and another object.
double W() const
Returns W component of the 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.
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.
double Y() const
Returns Y component of the quaternion.
Quaternion(double w, double x, double y, double z)
Constructs a quaternion with the given components.
a class to store JSON values
Definition: json.h:2655
const Scalar & y
Definition: MathFunctions.h:821
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)
Definition: AprilTagFieldLayout.h:18