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