WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
Twist3d.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 "wpi/units/angle.hpp"
8#include "wpi/units/length.hpp"
9#include "wpi/units/math.hpp"
11
12namespace wpi::math {
13
14class Transform3d;
15
16/**
17 * A change in distance along a 3D arc since the last pose update. We can use
18 * ideas from differential calculus to create new Pose3ds from a Twist3d and
19 * vice versa.
20 *
21 * A Twist can be used to represent a difference between two poses.
22 */
24 /**
25 * Linear "dx" component
26 */
27 wpi::units::meter_t dx = 0_m;
28
29 /**
30 * Linear "dy" component
31 */
32 wpi::units::meter_t dy = 0_m;
33
34 /**
35 * Linear "dz" component
36 */
37 wpi::units::meter_t dz = 0_m;
38
39 /**
40 * Rotation vector x component.
41 */
42 wpi::units::radian_t rx = 0_rad;
43
44 /**
45 * Rotation vector y component.
46 */
47 wpi::units::radian_t ry = 0_rad;
48
49 /**
50 * Rotation vector z component.
51 */
52 wpi::units::radian_t rz = 0_rad;
53
54 /**
55 * Obtain a new Transform3d from a (constant curvature) velocity.
56 *
57 * See "https://file.tavsys.net/control/controls-engineering-in-frc.pdf"
58 * Controls Engineering in the FIRST Robotics Competition section 10.2
59 * "Pose exponential" for a derivation.
60 *
61 * The twist is a change in pose in the robot's coordinate frame since the
62 * previous pose update. When the user runs Exp() on the twist, the user will
63 * receive the pose delta.
64 *
65 * "Exp" represents the pose exponential, which is solving a differential
66 * equation moving the pose forward in time.
67 *
68 * @return The pose delta of the robot.
69 */
70 constexpr Transform3d Exp() const;
71
72 /**
73 * Checks equality between this Twist3d and another object.
74 *
75 * @param other The other object.
76 * @return Whether the two objects are equal.
77 */
78 constexpr bool operator==(const Twist3d& other) const {
79 return wpi::units::math::abs(dx - other.dx) < 1E-9_m &&
80 wpi::units::math::abs(dy - other.dy) < 1E-9_m &&
81 wpi::units::math::abs(dz - other.dz) < 1E-9_m &&
82 wpi::units::math::abs(rx - other.rx) < 1E-9_rad &&
83 wpi::units::math::abs(ry - other.ry) < 1E-9_rad &&
84 wpi::units::math::abs(rz - other.rz) < 1E-9_rad;
85 }
86
87 /**
88 * Scale this by a given factor.
89 *
90 * @param factor The factor by which to scale.
91 * @return The scaled Twist3d.
92 */
93 constexpr Twist3d operator*(double factor) const {
94 return Twist3d{dx * factor, dy * factor, dz * factor,
95 rx * factor, ry * factor, rz * factor};
96 }
97};
98
99} // namespace wpi::math
100
103
104namespace wpi::math {
105
106constexpr Transform3d Twist3d::Exp() const {
107 // Implementation from Section 3.2 of https://ethaneade.org/lie.pdf
108
109 auto impl = [this]<typename Matrix3d, typename Vector3d>() -> Transform3d {
110 Vector3d u{{dx.value(), dy.value(), dz.value()}};
111 Vector3d rvec{{rx.value(), ry.value(), rz.value()}};
112 Matrix3d omega = detail::RotationVectorToMatrix(rvec);
113 Matrix3d omegaSq = omega * omega;
114 double theta = rvec.norm();
115 double thetaSq = theta * theta;
116
117 double A;
118 double B;
119 double C;
120 if (gcem::abs(theta) < 1E-7) {
121 // Taylor Expansions around θ = 0
122 // A = 1/1! - θ²/3! + θ⁴/5!
123 // B = 1/2! - θ²/4! + θ⁴/6!
124 // C = 1/3! - θ²/5! + θ⁴/7!
125 // sources:
126 // A:
127 // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5Bsin%5C%2840%29x%5C%2841%29%2Cx%5D+at+x%3D0
128 // B:
129 // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5B1-cos%5C%2840%29x%5C%2841%29%2CPower%5Bx%2C2%5D%5D+at+x%3D0
130 // C:
131 // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5B1-Divide%5Bsin%5C%2840%29x%5C%2841%29%2Cx%5D%2CPower%5Bx%2C2%5D%5D+at+x%3D0
132 A = 1 - thetaSq / 6 + thetaSq * thetaSq / 120;
133 B = 1 / 2.0 - thetaSq / 24 + thetaSq * thetaSq / 720;
134 C = 1 / 6.0 - thetaSq / 120 + thetaSq * thetaSq / 5040;
135 } else {
136 // A = std::sin(θ)/θ
137 // B = (1 - std::cos(θ)) / θ²
138 // C = (1 - A) / θ²
139 A = gcem::sin(theta) / theta;
140 B = (1 - gcem::cos(theta)) / thetaSq;
141 C = (1 - A) / thetaSq;
142 }
143
144 Matrix3d R = Matrix3d::Identity() + A * omega + B * omegaSq;
145 Matrix3d V = Matrix3d::Identity() + B * omega + C * omegaSq;
146
147 Vector3d translation_component = V * u;
148
149 const Transform3d transform{
150 Translation3d{wpi::units::meter_t{translation_component(0)},
151 wpi::units::meter_t{translation_component(1)},
152 wpi::units::meter_t{translation_component(2)}},
153 Rotation3d{R}};
154
155 return transform;
156 };
157
158 if (std::is_constant_evaluated()) {
159 return impl.template operator()<ct_matrix3d, ct_vector3d>();
160 }
161 return impl.template operator()<Eigen::Matrix3d, Eigen::Vector3d>();
162}
163
164} // namespace wpi::math
165
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
Represents a transformation for a Pose3d in the pose's frame.
Definition Transform3d.hpp:23
Represents a translation in 3D space.
Definition Translation3d.hpp:31
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > cos(const T x) noexcept
Compile-time cosine function.
Definition cos.hpp:83
constexpr return_t< T > sin(const T x) noexcept
Compile-time sine function.
Definition sin.hpp:85
Definition RobotBase.hpp:26
constexpr ct_matrix3d RotationVectorToMatrix(const ct_vector3d &rotation)
Definition RotationVectorToMatrix.hpp:13
Definition LinearSystem.hpp:20
ct_vector< double, 3 > ct_vector3d
Definition ct_matrix.hpp:387
ct_matrix< double, 3, 3 > ct_matrix3d
Definition ct_matrix.hpp:385
A change in distance along a 3D arc since the last pose update.
Definition Twist3d.hpp:23
constexpr Transform3d Exp() const
Obtain a new Transform3d from a (constant curvature) velocity.
Definition Twist3d.hpp:106
wpi::units::meter_t dy
Linear "dy" component.
Definition Twist3d.hpp:32
constexpr Twist3d operator*(double factor) const
Scale this by a given factor.
Definition Twist3d.hpp:93
constexpr bool operator==(const Twist3d &other) const
Checks equality between this Twist3d and another object.
Definition Twist3d.hpp:78
wpi::units::radian_t rx
Rotation vector x component.
Definition Twist3d.hpp:42
wpi::units::meter_t dz
Linear "dz" component.
Definition Twist3d.hpp:37
wpi::units::meter_t dx
Linear "dx" component.
Definition Twist3d.hpp:27
wpi::units::radian_t rz
Rotation vector z component.
Definition Twist3d.hpp:52
wpi::units::radian_t ry
Rotation vector y component.
Definition Twist3d.hpp:47