WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
Rotation3d.hpp
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 <numbers>
8#include <type_traits>
9
10#include <Eigen/Core>
11#include <gcem.hpp>
12
16#include "wpi/units/angle.hpp"
17#include "wpi/units/math.hpp"
20
21namespace wpi::util {
22class json;
23} // namespace wpi::util
24
25namespace wpi::math {
26
27/**
28 * A rotation in a 3D coordinate frame, represented by a quaternion. Note that
29 * unlike 2D rotations, 3D rotations are not always commutative, so changing the
30 * order of rotations changes the result.
31 *
32 * As an example of the order of rotations mattering, suppose we have a card
33 * that looks like this:
34 *
35 * <pre>
36 *   ┌───┐ ┌───┐
37 * │ X │ │ x │
38 * Front: │ | │ Back: │ · │
39 * │ | │ │ · │
40 * └───┘ └───┘
41 * </pre>
42 *
43 * If we rotate 90º clockwise around the axis into the page, then flip around
44 * the left/right axis, we get one result:
45 *
46 * <pre>
47 *  ┌───┐
48 * │ X │ ┌───────┐ ┌───────┐
49 * │ | │ → │------X│ → │······x│
50 * │ | │ └───────┘ └───────┘
51 * └───┘
52 * </pre>
53 *
54 * If we flip around the left/right axis, then rotate 90º clockwise around the
55 * axis into the page, we get a different result:
56 *
57 * <pre>
58 *   ┌───┐ ┌───┐
59 * │ X │ │ · │ ┌───────┐
60 * │ | │ → │ · │ → │x······│
61 * │ | │ │ x │ └───────┘
62 * └───┘ └───┘
63 * </pre>
64 *
65 * Because order matters for 3D rotations, we need to distinguish between
66 * <em>extrinsic</em> rotations and <em>intrinsic</em> rotations. Rotating
67 * extrinsically means rotating around the global axes, while rotating
68 * intrinsically means rotating from the perspective of the other rotation. A
69 * neat property is that applying a series of rotations extrinsically is the
70 * same as applying the same series in the opposite order intrinsically.
71 */
73 public:
74 /**
75 * Constructs a Rotation3d representing no rotation.
76 */
77 constexpr Rotation3d() = default;
78
79 /**
80 * Constructs a Rotation3d from a quaternion.
81 *
82 * @param q The quaternion.
83 */
84 constexpr explicit Rotation3d(const Quaternion& q) { m_q = q.Normalize(); }
85
86 /**
87 * Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
88 *
89 * Extrinsic rotations occur in that order around the axes in the fixed global
90 * frame rather than the body frame.
91 *
92 * Angles are measured counterclockwise with the rotation axis pointing "out
93 * of the page". If you point your right thumb along the positive axis
94 * direction, your fingers curl in the direction of positive rotation.
95 *
96 * @param roll The counterclockwise rotation angle around the X axis (roll).
97 * @param pitch The counterclockwise rotation angle around the Y axis (pitch).
98 * @param yaw The counterclockwise rotation angle around the Z axis (yaw).
99 */
100 constexpr Rotation3d(wpi::units::radian_t roll, wpi::units::radian_t pitch,
101 wpi::units::radian_t yaw) {
102 // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion
103 double cr = wpi::units::math::cos(roll * 0.5);
104 double sr = wpi::units::math::sin(roll * 0.5);
105
106 double cp = wpi::units::math::cos(pitch * 0.5);
107 double sp = wpi::units::math::sin(pitch * 0.5);
108
109 double cy = wpi::units::math::cos(yaw * 0.5);
110 double sy = wpi::units::math::sin(yaw * 0.5);
111
112 m_q = Quaternion{cr * cp * cy + sr * sp * sy, sr * cp * cy - cr * sp * sy,
113 cr * sp * cy + sr * cp * sy, cr * cp * sy - sr * sp * cy};
114 }
115
116 /**
117 * Constructs a Rotation3d with the given axis-angle representation. The axis
118 * doesn't have to be normalized.
119 *
120 * @param axis The rotation axis.
121 * @param angle The rotation around the axis.
122 */
123 constexpr Rotation3d(const Eigen::Vector3d& axis,
124 wpi::units::radian_t angle) {
125 double norm = ct_matrix{axis}.norm();
126 if (norm == 0.0) {
127 return;
128 }
129
130 // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition
131 Eigen::Vector3d v{{axis(0) / norm * wpi::units::math::sin(angle / 2.0),
132 axis(1) / norm * wpi::units::math::sin(angle / 2.0),
133 axis(2) / norm * wpi::units::math::sin(angle / 2.0)}};
134 m_q = Quaternion{wpi::units::math::cos(angle / 2.0), v(0), v(1), v(2)};
135 }
136
137 /**
138 * Constructs a Rotation3d with the given rotation vector representation. This
139 * representation is equivalent to axis-angle, where the normalized axis is
140 * multiplied by the rotation around the axis in radians.
141 *
142 * @param rvec The rotation vector.
143 */
144 constexpr explicit Rotation3d(const Eigen::Vector3d& rvec)
145 : Rotation3d{rvec, wpi::units::radian_t{ct_matrix{rvec}.norm()}} {}
146
147 /**
148 * Constructs a Rotation3d from a rotation matrix.
149 *
150 * @param rotationMatrix The rotation matrix.
151 * @throws std::domain_error if the rotation matrix isn't special orthogonal.
152 */
153 constexpr explicit Rotation3d(const Eigen::Matrix3d& rotationMatrix) {
154 auto impl = []<typename Matrix3d>(const Matrix3d& R) -> Quaternion {
155 // Require that the rotation matrix is special orthogonal. This is true if
156 // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
157 if ((R * R.transpose() - Matrix3d::Identity()).norm() > 1e-9) {
158 throw std::domain_error("Rotation matrix isn't orthogonal");
159 }
160 // HACK: Uses ct_matrix instead of <Eigen/LU> for determinant because
161 // including <Eigen/LU> doubles compilation times on MSVC, even if
162 // this constructor is unused. MSVC's frontend inefficiently parses
163 // large headers; GCC and Clang are largely unaffected.
164 if (gcem::abs(ct_matrix{R}.determinant() - 1.0) > 1e-9) {
165 throw std::domain_error(
166 "Rotation matrix is orthogonal but not special orthogonal");
167 }
168
169 // Turn rotation matrix into a quaternion
170 // https://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/
171 double trace = R(0, 0) + R(1, 1) + R(2, 2);
172 double w;
173 double x;
174 double y;
175 double z;
176
177 if (trace > 0.0) {
178 double s = 0.5 / gcem::sqrt(trace + 1.0);
179 w = 0.25 / s;
180 x = (R(2, 1) - R(1, 2)) * s;
181 y = (R(0, 2) - R(2, 0)) * s;
182 z = (R(1, 0) - R(0, 1)) * s;
183 } else {
184 if (R(0, 0) > R(1, 1) && R(0, 0) > R(2, 2)) {
185 double s = 2.0 * gcem::sqrt(1.0 + R(0, 0) - R(1, 1) - R(2, 2));
186 w = (R(2, 1) - R(1, 2)) / s;
187 x = 0.25 * s;
188 y = (R(0, 1) + R(1, 0)) / s;
189 z = (R(0, 2) + R(2, 0)) / s;
190 } else if (R(1, 1) > R(2, 2)) {
191 double s = 2.0 * gcem::sqrt(1.0 + R(1, 1) - R(0, 0) - R(2, 2));
192 w = (R(0, 2) - R(2, 0)) / s;
193 x = (R(0, 1) + R(1, 0)) / s;
194 y = 0.25 * s;
195 z = (R(1, 2) + R(2, 1)) / s;
196 } else {
197 double s = 2.0 * gcem::sqrt(1.0 + R(2, 2) - R(0, 0) - R(1, 1));
198 w = (R(1, 0) - R(0, 1)) / s;
199 x = (R(0, 2) + R(2, 0)) / s;
200 y = (R(1, 2) + R(2, 1)) / s;
201 z = 0.25 * s;
202 }
203 }
204
205 return Quaternion{w, x, y, z};
206 };
207
208 if (std::is_constant_evaluated()) {
209 m_q = impl(ct_matrix3d{rotationMatrix});
210 } else {
211 m_q = impl(rotationMatrix);
212 }
213 }
214
215 /**
216 * Constructs a Rotation3d that rotates the initial vector onto the final
217 * vector.
218 *
219 * This is useful for turning a 3D vector (final) into an orientation relative
220 * to a coordinate system vector (initial).
221 *
222 * @param initial The initial vector.
223 * @param final The final vector.
224 */
225 constexpr Rotation3d(const Eigen::Vector3d& initial,
226 const Eigen::Vector3d& final) {
227 double dot = ct_matrix{initial}.dot(ct_matrix{final});
228 double normProduct = ct_matrix{initial}.norm() * ct_matrix{final}.norm();
229 double dotNorm = dot / normProduct;
230
231 if (dotNorm > 1.0 - 1E-9) {
232 // If the dot product is 1, the two vectors point in the same direction so
233 // there's no rotation. The default initialization of m_q will work.
234 return;
235 } else if (dotNorm < -1.0 + 1E-9) {
236 // If the dot product is -1, the two vectors are antiparallel, so a 180°
237 // rotation is required. Any other vector can be used to generate an
238 // orthogonal one.
239
240 double x = gcem::abs(initial(0));
241 double y = gcem::abs(initial(1));
242 double z = gcem::abs(initial(2));
243
244 // Find vector that is most orthogonal to initial vector
245 Eigen::Vector3d other;
246 if (x < y) {
247 if (x < z) {
248 // Use x-axis
249 other = Eigen::Vector3d{{1, 0, 0}};
250 } else {
251 // Use z-axis
252 other = Eigen::Vector3d{{0, 0, 1}};
253 }
254 } else {
255 if (y < z) {
256 // Use y-axis
257 other = Eigen::Vector3d{{0, 1, 0}};
258 } else {
259 // Use z-axis
260 other = Eigen::Vector3d{{0, 0, 1}};
261 }
262 }
263
264 auto axis = ct_matrix{initial}.cross(ct_matrix{other});
265
266 double axisNorm = axis.norm();
267 m_q = Quaternion{0.0, axis(0) / axisNorm, axis(1) / axisNorm,
268 axis(2) / axisNorm};
269 } else {
270 auto axis = ct_matrix{initial}.cross(final);
271
272 // https://stackoverflow.com/a/11741520
273 m_q =
274 Quaternion{normProduct + dot, axis(0), axis(1), axis(2)}.Normalize();
275 }
276 }
277
278 /**
279 * Constructs a 3D rotation from a 2D rotation in the X-Y plane.
280 *
281 * @param rotation The 2D rotation.
282 * @see Pose3d(Pose2d)
283 * @see Transform3d(Transform2d)
284 */
285 constexpr explicit Rotation3d(const Rotation2d& rotation)
286 : Rotation3d{0_rad, 0_rad, rotation.Radians()} {}
287
288 /**
289 * Takes the inverse of the current rotation.
290 *
291 * @return The inverse of the current rotation.
292 */
293 constexpr Rotation3d Inverse() const { return Rotation3d{m_q.Inverse()}; }
294
295 /**
296 * Multiplies the current rotation by a scalar.
297 *
298 * @param scalar The scalar.
299 *
300 * @return The new scaled Rotation3d.
301 */
302 constexpr Rotation3d operator*(double scalar) const {
303 return Rotation3d{}.Interpolate(*this, scalar);
304 }
305
306 /**
307 * Divides the current rotation by a scalar.
308 *
309 * @param scalar The scalar.
310 *
311 * @return The new scaled Rotation3d.
312 */
313 constexpr Rotation3d operator/(double scalar) const {
314 return *this * (1.0 / scalar);
315 }
316
317 /**
318 * Checks equality between this Rotation3d and another object.
319 */
320 constexpr bool operator==(const Rotation3d& other) const {
321 return gcem::abs(gcem::abs(m_q.Dot(other.m_q)) -
322 m_q.Norm() * other.m_q.Norm()) < 1e-9;
323 }
324
325 /**
326 * Adds the new rotation to the current rotation. The other rotation is
327 * applied extrinsically, which means that it rotates around the global axes.
328 * For example, Rotation3d{90_deg, 0, 0}.RotateBy(Rotation3d{0, 45_deg, 0})
329 * rotates by 90 degrees around the +X axis and then by 45 degrees around the
330 * global +Y axis. (This is equivalent to Rotation3d{90_deg, 45_deg, 0})
331 *
332 * @param other The extrinsic rotation to rotate by.
333 *
334 * @return The new rotated Rotation3d.
335 */
336 constexpr Rotation3d RotateBy(const Rotation3d& other) const {
337 return Rotation3d{other.m_q * m_q};
338 }
339
340 /**
341 * Returns the current rotation relative to the given rotation. Because the
342 * result is in the perspective of the given rotation, it must be applied
343 * intrinsically. See the class comment for definitions of extrinsic and
344 * intrinsic rotations.
345 *
346 * @param other The rotation describing the orientation of the new coordinate
347 * frame that the current rotation will be converted into.
348 *
349 * @return The current rotation relative to the new orientation of the
350 * coordinate frame.
351 */
352 constexpr Rotation3d RelativeTo(const Rotation3d& other) const {
353 // To apply a quaternion intrinsically, we must right-multiply by that
354 // quaternion. Therefore, "this_q relative to other_q" is the q such that
355 // other_q q = this_q:
356 //
357 // other_q q = this_q
358 // q = other_q⁻¹ this_q
359 return Rotation3d{other.m_q.Inverse() * m_q};
360 }
361
362 /**
363 * Interpolates between this rotation and another.
364 *
365 * @param endValue The other rotation.
366 * @param t How far between the two rotations we are (0 means this rotation, 1
367 * means other rotation).
368 * @return The interpolated value.
369 */
370 constexpr Rotation3d Interpolate(Rotation3d endValue, double t) const {
371 // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp
372 //
373 // slerp(q₀, q₁, t) = (q₁q₀⁻¹)ᵗq₀
374 //
375 // We negate the delta quaternion if necessary to take the shortest path
376 const auto& q0 = m_q;
377 const auto& q1 = endValue.m_q;
378 auto delta = q1 * q0.Inverse();
379 if (delta.W() < 0.0) {
380 delta = Quaternion{-delta.W(), -delta.X(), -delta.Y(), -delta.Z()};
381 }
382 return Rotation3d{delta.Pow(t) * q0};
383 }
384
385 /**
386 * Returns the quaternion representation of the Rotation3d.
387 */
388 constexpr const Quaternion& GetQuaternion() const { return m_q; }
389
390 /**
391 * Returns the counterclockwise rotation angle around the X axis (roll).
392 */
393 constexpr wpi::units::radian_t X() const {
394 double w = m_q.W();
395 double x = m_q.X();
396 double y = m_q.Y();
397 double z = m_q.Z();
398
399 // wpimath/algorithms.md
400 double cxcy = 1.0 - 2.0 * (x * x + y * y);
401 double sxcy = 2.0 * (w * x + y * z);
402 double cy_sq = cxcy * cxcy + sxcy * sxcy;
403 if (cy_sq > 1e-20) {
404 return wpi::units::radian_t{gcem::atan2(sxcy, cxcy)};
405 } else {
406 return 0_rad;
407 }
408 }
409
410 /**
411 * Returns the counterclockwise rotation angle around the Y axis (pitch).
412 */
413 constexpr wpi::units::radian_t Y() const {
414 double w = m_q.W();
415 double x = m_q.X();
416 double y = m_q.Y();
417 double z = m_q.Z();
418
419 // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion
420 double ratio = 2.0 * (w * y - z * x);
421 if (gcem::abs(ratio) >= 1.0) {
422 return wpi::units::radian_t{
423 gcem::copysign(std::numbers::pi / 2.0, ratio)};
424 } else {
425 return wpi::units::radian_t{gcem::asin(ratio)};
426 }
427 }
428
429 /**
430 * Returns the counterclockwise rotation angle around the Z axis (yaw).
431 */
432 constexpr wpi::units::radian_t Z() const {
433 double w = m_q.W();
434 double x = m_q.X();
435 double y = m_q.Y();
436 double z = m_q.Z();
437
438 // wpimath/algorithms.md
439 double cycz = 1.0 - 2.0 * (y * y + z * z);
440 double cysz = 2.0 * (w * z + x * y);
441 double cy_sq = cycz * cycz + cysz * cysz;
442 if (cy_sq > 1e-20) {
443 return wpi::units::radian_t{gcem::atan2(cysz, cycz)};
444 } else {
445 return wpi::units::radian_t{gcem::atan2(2.0 * w * z, w * w - z * z)};
446 }
447 }
448
449 /**
450 * Returns the axis in the axis-angle representation of this rotation.
451 */
452 constexpr Eigen::Vector3d Axis() const {
453 double norm = gcem::hypot(m_q.X(), m_q.Y(), m_q.Z());
454 if (norm == 0.0) {
455 return Eigen::Vector3d{{0.0, 0.0, 0.0}};
456 } else {
457 return Eigen::Vector3d{{m_q.X() / norm, m_q.Y() / norm, m_q.Z() / norm}};
458 }
459 }
460
461 /**
462 * Returns the angle in the axis-angle representation of this rotation.
463 */
464 constexpr wpi::units::radian_t Angle() const {
465 double norm = gcem::hypot(m_q.X(), m_q.Y(), m_q.Z());
466 return wpi::units::radian_t{2.0 * gcem::atan2(norm, m_q.W())};
467 }
468
469 /**
470 * Returns rotation matrix representation of this rotation.
471 */
472 constexpr Eigen::Matrix3d ToMatrix() const {
473 double w = m_q.W();
474 double x = m_q.X();
475 double y = m_q.Y();
476 double z = m_q.Z();
477
478 // https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation#Quaternion-derived_rotation_matrix
479 return Eigen::Matrix3d{{1.0 - 2.0 * (y * y + z * z), 2.0 * (x * y - w * z),
480 2.0 * (x * z + w * y)},
481 {2.0 * (x * y + w * z), 1.0 - 2.0 * (x * x + z * z),
482 2.0 * (y * z - w * x)},
483 {2.0 * (x * z - w * y), 2.0 * (y * z + w * x),
484 1.0 - 2.0 * (x * x + y * y)}};
485 }
486
487 /**
488 * Returns rotation vector representation of this rotation.
489 *
490 * @return Rotation vector representation of this rotation.
491 */
492 constexpr Eigen::Vector3d ToVector() const { return m_q.ToRotationVector(); }
493
494 /**
495 * Returns a Rotation2d representing this Rotation3d projected into the X-Y
496 * plane.
497 */
498 constexpr Rotation2d ToRotation2d() const { return Rotation2d{Z()}; }
499
500 private:
501 Quaternion m_q;
502};
503
505void to_json(wpi::util::json& json, const Rotation3d& rotation);
506
508void from_json(const wpi::util::json& json, Rotation3d& rotation);
509
510} // namespace wpi::math
511
512template <>
514 const wpi::math::Rotation3d& startValue,
515 const wpi::math::Rotation3d& endValue, double t) {
516 return startValue.Interpolate(endValue, t);
517}
518
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a quaternion.
Definition Quaternion.hpp:23
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.hpp:134
constexpr Quaternion Normalize() const
Normalizes the quaternion.
Definition Quaternion.hpp:142
constexpr double Norm() const
Calculates the L2 norm of the quaternion.
Definition Quaternion.hpp:154
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:29
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:72
constexpr wpi::units::radian_t X() const
Returns the counterclockwise rotation angle around the X axis (roll).
Definition Rotation3d.hpp:393
constexpr Rotation2d ToRotation2d() const
Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
Definition Rotation3d.hpp:498
constexpr Eigen::Vector3d ToVector() const
Returns rotation vector representation of this rotation.
Definition Rotation3d.hpp:492
constexpr Rotation3d operator/(double scalar) const
Divides the current rotation by a scalar.
Definition Rotation3d.hpp:313
constexpr Rotation3d(const Eigen::Matrix3d &rotationMatrix)
Constructs a Rotation3d from a rotation matrix.
Definition Rotation3d.hpp:153
constexpr const Quaternion & GetQuaternion() const
Returns the quaternion representation of the Rotation3d.
Definition Rotation3d.hpp:388
constexpr Rotation3d Interpolate(Rotation3d endValue, double t) const
Interpolates between this rotation and another.
Definition Rotation3d.hpp:370
constexpr Rotation3d()=default
Constructs a Rotation3d representing no rotation.
constexpr Rotation3d(const Quaternion &q)
Constructs a Rotation3d from a quaternion.
Definition Rotation3d.hpp:84
constexpr Eigen::Vector3d Axis() const
Returns the axis in the axis-angle representation of this rotation.
Definition Rotation3d.hpp:452
constexpr Rotation3d(wpi::units::radian_t roll, wpi::units::radian_t pitch, wpi::units::radian_t yaw)
Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
Definition Rotation3d.hpp:100
constexpr Rotation3d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Definition Rotation3d.hpp:302
constexpr wpi::units::radian_t Z() const
Returns the counterclockwise rotation angle around the Z axis (yaw).
Definition Rotation3d.hpp:432
constexpr Rotation3d Inverse() const
Takes the inverse of the current rotation.
Definition Rotation3d.hpp:293
constexpr wpi::units::radian_t Angle() const
Returns the angle in the axis-angle representation of this rotation.
Definition Rotation3d.hpp:464
constexpr Rotation3d(const Eigen::Vector3d &rvec)
Constructs a Rotation3d with the given rotation vector representation.
Definition Rotation3d.hpp:144
constexpr Eigen::Matrix3d ToMatrix() const
Returns rotation matrix representation of this rotation.
Definition Rotation3d.hpp:472
constexpr Rotation3d(const Eigen::Vector3d &initial, const Eigen::Vector3d &final)
Constructs a Rotation3d that rotates the initial vector onto the final vector.
Definition Rotation3d.hpp:225
constexpr bool operator==(const Rotation3d &other) const
Checks equality between this Rotation3d and another object.
Definition Rotation3d.hpp:320
constexpr Rotation3d RelativeTo(const Rotation3d &other) const
Returns the current rotation relative to the given rotation.
Definition Rotation3d.hpp:352
constexpr Rotation3d(const Eigen::Vector3d &axis, wpi::units::radian_t angle)
Constructs a Rotation3d with the given axis-angle representation.
Definition Rotation3d.hpp:123
constexpr wpi::units::radian_t Y() const
Returns the counterclockwise rotation angle around the Y axis (pitch).
Definition Rotation3d.hpp:413
constexpr Rotation3d(const Rotation2d &rotation)
Constructs a 3D rotation from a 2D rotation in the X-Y plane.
Definition Rotation3d.hpp:285
constexpr Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Definition Rotation3d.hpp:336
Compile-time wrapper for Eigen::Matrix.
Definition ct_matrix.hpp:26
constexpr ct_matrix< Scalar, 3, 1 > cross(const ct_matrix< Scalar, 3, 1 > &rhs)
Constexpr version of Eigen's 3D vector cross member function.
Definition ct_matrix.hpp:303
constexpr Scalar dot(const ct_matrix< Scalar, RhsRows, RhsCols > &rhs) const
Constexpr version of Eigen's vector dot member function.
Definition ct_matrix.hpp:262
constexpr Scalar norm() const
Constexpr version of Eigen's norm member function.
Definition ct_matrix.hpp:281
constexpr Scalar determinant() const
Constexpr version of Eigen's 2x2 matrix determinant member function.
Definition ct_matrix.hpp:316
Definition json.hpp:85
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > asin(const T x) noexcept
Compile-time arcsine function.
Definition asin.hpp:82
constexpr T1 copysign(const T1 x, const T2 y) noexcept
Compile-time copy sign function.
Definition copysign.hpp:41
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
constexpr return_t< T > sqrt(const T x) noexcept
Compile-time square-root function.
Definition sqrt.hpp:109
constexpr common_return_t< T1, T2 > atan2(const T1 y, const T2 x) noexcept
Compile-time two-argument arctangent function.
Definition atan2.hpp:88
Definition RobotBase.hpp:26
Definition LinearSystem.hpp:20
ct_matrix< double, 3, 3 > ct_matrix3d
Definition ct_matrix.hpp:385
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
Definition raw_os_ostream.hpp:19
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.hpp:780
Definition CvSource.hpp:15