WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
Spline.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 <optional>
8#include <utility>
9
10#include <gcem.hpp>
11#include <wpi/array.h>
12
13#include "frc/EigenCore.h"
14#include "frc/geometry/Pose2d.h"
15#include "units/curvature.h"
16#include "units/length.h"
17
18namespace frc {
19
20/**
21 * Represents a two-dimensional parametric spline that interpolates between two
22 * points.
23 *
24 * @tparam Degree The degree of the spline.
25 */
26template <int Degree>
27class Spline {
28 public:
29 using PoseWithCurvature = std::pair<Pose2d, units::curvature_t>;
30
31 constexpr Spline() = default;
32
33 constexpr Spline(const Spline&) = default;
34 constexpr Spline& operator=(const Spline&) = default;
35
36 constexpr Spline(Spline&&) = default;
37 constexpr Spline& operator=(Spline&&) = default;
38
39 constexpr virtual ~Spline() = default;
40
41 /**
42 * Represents a control vector for a spline.
43 *
44 * Each element in each array represents the value of the derivative at the
45 * index. For example, the value of x[2] is the second derivative in the x
46 * dimension.
47 */
49 /// The x components of the control vector.
50 wpi::array<double, (Degree + 1) / 2> x;
51
52 /// The y components of the control vector.
53 wpi::array<double, (Degree + 1) / 2> y;
54 };
55
56 /**
57 * Gets the pose and curvature at some point t on the spline.
58 *
59 * @param t The point t
60 * @return The pose and curvature at that point.
61 */
62 std::optional<PoseWithCurvature> GetPoint(double t) const {
63 Vectord<Degree + 1> polynomialBases;
64
65 // Populate the polynomial bases
66 for (int i = 0; i <= Degree; i++) {
67 polynomialBases(i) = gcem::pow(t, Degree - i);
68 }
69
70 // This simply multiplies by the coefficients. We need to divide out t some
71 // n number of times where n is the derivative we want to take.
72 Vectord<6> combined = Coefficients() * polynomialBases;
73
74 double dx, dy, ddx, ddy;
75
76 // If t = 0, all other terms in the equation cancel out to zero. We can use
77 // the last x^0 term in the equation.
78 if (t == 0.0) {
79 dx = Coefficients()(2, Degree - 1);
80 dy = Coefficients()(3, Degree - 1);
81 ddx = Coefficients()(4, Degree - 2);
82 ddy = Coefficients()(5, Degree - 2);
83 } else {
84 // Divide out t for first derivative.
85 dx = combined(2) / t;
86 dy = combined(3) / t;
87
88 // Divide out t for second derivative.
89 ddx = combined(4) / t / t;
90 ddy = combined(5) / t / t;
91 }
92
93 if (gcem::hypot(dx, dy) < 1e-6) {
94 return std::nullopt;
95 }
96
97 // Find the curvature.
98 const auto curvature =
99 (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) * gcem::hypot(dx, dy));
100
101 return PoseWithCurvature{
102 {FromVector(combined.template block<2, 1>(0, 0)), Rotation2d{dx, dy}},
103 units::curvature_t{curvature}};
104 }
105
106 /**
107 * Returns the coefficients of the spline.
108 *
109 * @return The coefficients of the spline.
110 */
111 constexpr virtual Matrixd<6, Degree + 1> Coefficients() const = 0;
112
113 /**
114 * Returns the initial control vector that created this spline.
115 *
116 * @return The initial control vector that created this spline.
117 */
118 constexpr virtual const ControlVector& GetInitialControlVector() const = 0;
119
120 /**
121 * Returns the final control vector that created this spline.
122 *
123 * @return The final control vector that created this spline.
124 */
125 constexpr virtual const ControlVector& GetFinalControlVector() const = 0;
126
127 protected:
128 /**
129 * Converts a Translation2d into a vector that is compatible with Eigen.
130 *
131 * @param translation The Translation2d to convert.
132 * @return The vector.
133 */
134 static constexpr Eigen::Vector2d ToVector(const Translation2d& translation) {
135 return Eigen::Vector2d{{translation.X().value()},
136 {translation.Y().value()}};
137 }
138
139 /**
140 * Converts an Eigen vector into a Translation2d.
141 *
142 * @param vector The vector to convert.
143 * @return The Translation2d.
144 */
145 static constexpr Translation2d FromVector(const Eigen::Vector2d& vector) {
146 return Translation2d{units::meter_t{vector(0)}, units::meter_t{vector(1)}};
147 }
148};
149
150} // namespace frc
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Represents a two-dimensional parametric spline that interpolates between two points.
Definition Spline.h:27
constexpr Spline()=default
virtual constexpr const ControlVector & GetInitialControlVector() const =0
Returns the initial control vector that created this spline.
constexpr Spline & operator=(const Spline &)=default
static constexpr Translation2d FromVector(const Eigen::Vector2d &vector)
Converts an Eigen vector into a Translation2d.
Definition Spline.h:145
virtual constexpr ~Spline()=default
constexpr Spline & operator=(Spline &&)=default
static constexpr Eigen::Vector2d ToVector(const Translation2d &translation)
Converts a Translation2d into a vector that is compatible with Eigen.
Definition Spline.h:134
constexpr Spline(Spline &&)=default
constexpr Spline(const Spline &)=default
virtual constexpr Matrixd< 6, Degree+1 > Coefficients() const =0
Returns the coefficients of the spline.
std::pair< Pose2d, units::curvature_t > PoseWithCurvature
Definition Spline.h:29
virtual constexpr const ControlVector & GetFinalControlVector() const =0
Returns the final control vector that created this spline.
std::optional< PoseWithCurvature > GetPoint(double t) const
Gets the pose and curvature at some point t on the spline.
Definition Spline.h:62
Represents a translation in 2D space.
Definition Translation2d.h:29
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:90
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Definition CAN.h:11
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
constexpr common_t< T1, T2 > pow(const T1 base, const T2 exp_term) noexcept
Compile-time power function.
Definition pow.hpp:82
Represents a control vector for a spline.
Definition Spline.h:48
wpi::array< double,(Degree+1)/2 > x
The x components of the control vector.
Definition Spline.h:50
wpi::array< double,(Degree+1)/2 > y
The y components of the control vector.
Definition Spline.h:53