WPILibC++ 2024.3.2
Rotation3d.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 <Eigen/Core>
8#include <wpi/SymbolExports.h>
9#include <wpi/json_fwd.h>
10
13#include "units/angle.h"
14
15namespace frc {
16
17/**
18 * A rotation in a 3D coordinate frame represented by a quaternion.
19 */
21 public:
22 /**
23 * Constructs a Rotation3d with a default angle of 0 degrees.
24 */
25 Rotation3d() = default;
26
27 /**
28 * Constructs a Rotation3d from a quaternion.
29 *
30 * @param q The quaternion.
31 */
32 explicit Rotation3d(const Quaternion& q);
33
34 /**
35 * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
36 *
37 * Extrinsic rotations occur in that order around the axes in the fixed global
38 * frame rather than the body frame.
39 *
40 * Angles are measured counterclockwise with the rotation axis pointing "out
41 * of the page". If you point your right thumb along the positive axis
42 * direction, your fingers curl in the direction of positive rotation.
43 *
44 * @param roll The counterclockwise rotation angle around the X axis (roll).
45 * @param pitch The counterclockwise rotation angle around the Y axis (pitch).
46 * @param yaw The counterclockwise rotation angle around the Z axis (yaw).
47 */
48 Rotation3d(units::radian_t roll, units::radian_t pitch, units::radian_t yaw);
49
50 /**
51 * Constructs a Rotation3d with the given axis-angle representation. The axis
52 * doesn't have to be normalized.
53 *
54 * @param axis The rotation axis.
55 * @param angle The rotation around the axis.
56 */
57 Rotation3d(const Eigen::Vector3d& axis, units::radian_t angle);
58
59 /**
60 * Constructs a Rotation3d with the given rotation vector representation. This
61 * representation is equivalent to axis-angle, where the normalized axis is
62 * multiplied by the rotation around the axis in radians.
63 *
64 * @param rvec The rotation vector.
65 */
66 explicit Rotation3d(const Eigen::Vector3d& rvec);
67
68 /**
69 * Constructs a Rotation3d from a rotation matrix.
70 *
71 * @param rotationMatrix The rotation matrix.
72 * @throws std::domain_error if the rotation matrix isn't special orthogonal.
73 */
74 explicit Rotation3d(const Eigen::Matrix3d& rotationMatrix);
75
76 /**
77 * Constructs a Rotation3d that rotates the initial vector onto the final
78 * vector.
79 *
80 * This is useful for turning a 3D vector (final) into an orientation relative
81 * to a coordinate system vector (initial).
82 *
83 * @param initial The initial vector.
84 * @param final The final vector.
85 */
86 Rotation3d(const Eigen::Vector3d& initial, const Eigen::Vector3d& final);
87
88 /**
89 * Adds two rotations together.
90 *
91 * @param other The rotation to add.
92 *
93 * @return The sum of the two rotations.
94 */
95 Rotation3d operator+(const Rotation3d& other) const;
96
97 /**
98 * Subtracts the new rotation from the current rotation and returns the new
99 * rotation.
100 *
101 * @param other The rotation to subtract.
102 *
103 * @return The difference between the two rotations.
104 */
105 Rotation3d operator-(const Rotation3d& other) const;
106
107 /**
108 * Takes the inverse of the current rotation.
109 *
110 * @return The inverse of the current rotation.
111 */
113
114 /**
115 * Multiplies the current rotation by a scalar.
116 *
117 * @param scalar The scalar.
118 *
119 * @return The new scaled Rotation3d.
120 */
122
123 /**
124 * Divides the current rotation by a scalar.
125 *
126 * @param scalar The scalar.
127 *
128 * @return The new scaled Rotation3d.
129 */
131
132 /**
133 * Checks equality between this Rotation3d and another object.
134 */
135 bool operator==(const Rotation3d&) const;
136
137 /**
138 * Adds the new rotation to the current rotation. The other rotation is
139 * applied extrinsically, which means that it rotates around the global axes.
140 * For example, Rotation3d{90_deg, 0, 0}.RotateBy(Rotation3d{0, 45_deg, 0})
141 * rotates by 90 degrees around the +X axis and then by 45 degrees around the
142 * global +Y axis. (This is equivalent to Rotation3d{90_deg, 45_deg, 0})
143 *
144 * @param other The extrinsic rotation to rotate by.
145 *
146 * @return The new rotated Rotation3d.
147 */
148 Rotation3d RotateBy(const Rotation3d& other) const;
149
150 /**
151 * Returns the quaternion representation of the Rotation3d.
152 */
153 const Quaternion& GetQuaternion() const;
154
155 /**
156 * Returns the counterclockwise rotation angle around the X axis (roll).
157 */
158 units::radian_t X() const;
159
160 /**
161 * Returns the counterclockwise rotation angle around the Y axis (pitch).
162 */
163 units::radian_t Y() const;
164
165 /**
166 * Returns the counterclockwise rotation angle around the Z axis (yaw).
167 */
168 units::radian_t Z() const;
169
170 /**
171 * Returns the axis in the axis-angle representation of this rotation.
172 */
173 Eigen::Vector3d Axis() const;
174
175 /**
176 * Returns the angle in the axis-angle representation of this rotation.
177 */
178 units::radian_t Angle() const;
179
180 /**
181 * Returns a Rotation2d representing this Rotation3d projected into the X-Y
182 * plane.
183 */
185
186 private:
187 Quaternion m_q;
188};
189
191void to_json(wpi::json& json, const Rotation3d& rotation);
192
194void from_json(const wpi::json& json, Rotation3d& rotation);
195
196} // namespace frc
197
#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