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