WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
CubicHermiteSpline.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
10#include "wpi/util/array.hpp"
11
12namespace wpi::math {
13/**
14 * Represents a hermite spline of degree 3.
15 */
17 public:
18 /**
19 * Constructs a cubic hermite spline with the specified control vectors. Each
20 * control vector contains info about the location of the point and its first
21 * derivative.
22 *
23 * @param xInitialControlVector The control vector for the initial point in
24 * the x dimension.
25 * @param xFinalControlVector The control vector for the final point in
26 * the x dimension.
27 * @param yInitialControlVector The control vector for the initial point in
28 * the y dimension.
29 * @param yFinalControlVector The control vector for the final point in
30 * the y dimension.
31 */
33 wpi::util::array<double, 2> xFinalControlVector,
34 wpi::util::array<double, 2> yInitialControlVector,
35 wpi::util::array<double, 2> yFinalControlVector)
36 : m_initialControlVector{xInitialControlVector, yInitialControlVector},
37 m_finalControlVector{xFinalControlVector, yFinalControlVector} {
38 const auto hermite = MakeHermiteBasis();
39 const auto x =
40 ControlVectorFromArrays(xInitialControlVector, xFinalControlVector);
41 const auto y =
42 ControlVectorFromArrays(yInitialControlVector, yFinalControlVector);
43
44 // Populate first two rows with coefficients.
45 m_coefficients.template block<1, 4>(0, 0) = hermite * x;
46 m_coefficients.template block<1, 4>(1, 0) = hermite * y;
47
48 // Populate Row 2 and Row 3 with the derivatives of the equations above.
49 // Then populate row 4 and 5 with the second derivatives.
50 for (int i = 0; i < 4; i++) {
51 // Here, we are multiplying by (3 - i) to manually take the derivative.
52 // The power of the term in index 0 is 3, index 1 is 2 and so on. To find
53 // the coefficient of the derivative, we can use the power rule and
54 // multiply the existing coefficient by its power.
55 m_coefficients.template block<2, 1>(2, i) =
56 m_coefficients.template block<2, 1>(0, i) * (3 - i);
57 }
58
59 for (int i = 0; i < 3; i++) {
60 // Here, we are multiplying by (2 - i) to manually take the derivative.
61 // The power of the term in index 0 is 2, index 1 is 1 and so on. To find
62 // the coefficient of the derivative, we can use the power rule and
63 // multiply the existing coefficient by its power.
64 m_coefficients.template block<2, 1>(4, i) =
65 m_coefficients.template block<2, 1>(2, i) * (2 - i);
66 }
67 }
68
69 /**
70 * Returns the coefficients matrix.
71 * @return The coefficients matrix.
72 */
73 Matrixd<6, 3 + 1> Coefficients() const override { return m_coefficients; }
74
75 /**
76 * Returns the initial control vector that created this spline.
77 *
78 * @return The initial control vector that created this spline.
79 */
80 const ControlVector& GetInitialControlVector() const override {
81 return m_initialControlVector;
82 }
83
84 /**
85 * Returns the final control vector that created this spline.
86 *
87 * @return The final control vector that created this spline.
88 */
89 const ControlVector& GetFinalControlVector() const override {
90 return m_finalControlVector;
91 }
92
93 private:
94 Matrixd<6, 4> m_coefficients = Matrixd<6, 4>::Zero();
95
96 ControlVector m_initialControlVector;
97 ControlVector m_finalControlVector;
98
99 /**
100 * Returns the hermite basis matrix for cubic hermite spline interpolation.
101 * @return The hermite basis matrix for cubic hermite spline interpolation.
102 */
103 static constexpr Eigen::Matrix4d MakeHermiteBasis() {
104 // Given P(i), P'(i), P(i+1), P'(i+1), the control vectors, we want to find
105 // the coefficients of the spline P(t) = a₃t³ + a₂t² + a₁t + a₀.
106 //
107 // P(i) = P(0) = a₀
108 // P'(i) = P'(0) = a₁
109 // P(i+1) = P(1) = a₃ + a₂ + a₁ + a₀
110 // P'(i+1) = P'(1) = 3a₃ + 2a₂ + a₁
111 //
112 // [P(i) ] = [0 0 0 1][a₃]
113 // [P'(i) ] = [0 0 1 0][a₂]
114 // [P(i+1) ] = [1 1 1 1][a₁]
115 // [P'(i+1)] = [3 2 1 0][a₀]
116 //
117 // To solve for the coefficients, we can invert the 4x4 matrix and move it
118 // to the other side of the equation.
119 //
120 // [a₃] = [ 2 1 -2 1][P(i) ]
121 // [a₂] = [-3 -2 3 -1][P'(i) ]
122 // [a₁] = [ 0 1 0 0][P(i+1) ]
123 // [a₀] = [ 1 0 0 0][P'(i+1)]
124 return Eigen::Matrix4d{{+2.0, +1.0, -2.0, +1.0},
125 {-3.0, -2.0, +3.0, -1.0},
126 {+0.0, +1.0, +0.0, +0.0},
127 {+1.0, +0.0, +0.0, +0.0}};
128 }
129
130 /**
131 * Returns the control vector for each dimension as a matrix from the
132 * user-provided arrays in the constructor.
133 *
134 * @param initialVector The control vector for the initial point.
135 * @param finalVector The control vector for the final point.
136 *
137 * @return The control vector matrix for a dimension.
138 */
139 static constexpr Eigen::Vector4d ControlVectorFromArrays(
140 wpi::util::array<double, 2> initialVector,
141 wpi::util::array<double, 2> finalVector) {
142 return Eigen::Vector4d{{initialVector[0]},
143 {initialVector[1]},
144 {finalVector[0]},
145 {finalVector[1]}};
146 }
147};
148} // namespace wpi::math
149
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
CubicHermiteSpline(wpi::util::array< double, 2 > xInitialControlVector, wpi::util::array< double, 2 > xFinalControlVector, wpi::util::array< double, 2 > yInitialControlVector, wpi::util::array< double, 2 > yFinalControlVector)
Constructs a cubic hermite spline with the specified control vectors.
Definition CubicHermiteSpline.hpp:32
const ControlVector & GetInitialControlVector() const override
Returns the initial control vector that created this spline.
Definition CubicHermiteSpline.hpp:80
Matrixd< 6, 3+1 > Coefficients() const override
Returns the coefficients matrix.
Definition CubicHermiteSpline.hpp:73
const ControlVector & GetFinalControlVector() const override
Returns the final control vector that created this spline.
Definition CubicHermiteSpline.hpp:89
constexpr Spline()=default
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.hpp:21
array(T, Ts...) -> array< T, 1+sizeof...(Ts)>