From 98d61e224401db4684b4db47e5447c44f106aeef Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 3 Jan 2025 17:35:07 -0800 Subject: [PATCH] Remove Eigen shim header --- .../trajopt/spline/CubicHermiteSpline.hpp | 12 ++++++++--- .../include/trajopt/spline/EigenCore.hpp | 21 ------------------- trajoptlib/include/trajopt/spline/Spline.hpp | 9 ++++---- 3 files changed, 14 insertions(+), 28 deletions(-) delete mode 100644 trajoptlib/include/trajopt/spline/EigenCore.hpp diff --git a/trajoptlib/include/trajopt/spline/CubicHermiteSpline.hpp b/trajoptlib/include/trajopt/spline/CubicHermiteSpline.hpp index 8fafa8055..2d28e3531 100644 --- a/trajoptlib/include/trajopt/spline/CubicHermiteSpline.hpp +++ b/trajoptlib/include/trajopt/spline/CubicHermiteSpline.hpp @@ -2,12 +2,14 @@ #pragma once -#include "trajopt/spline/EigenCore.hpp" +#include + #include "trajopt/spline/Spline.hpp" #include "trajopt/spline/array.hpp" #include "trajopt/util/SymbolExports.hpp" namespace frc { + /** * Represents a hermite spline of degree 3. */ @@ -36,7 +38,9 @@ class TRAJOPT_DLLEXPORT CubicHermiteSpline : public Spline<3> { * Returns the coefficients matrix. * @return The coefficients matrix. */ - Matrixd<6, 3 + 1> Coefficients() const override { return m_coefficients; } + Eigen::Matrix Coefficients() const override { + return m_coefficients; + } /** * Returns the initial control vector that created this spline. @@ -57,7 +61,8 @@ class TRAJOPT_DLLEXPORT CubicHermiteSpline : public Spline<3> { } private: - Matrixd<6, 4> m_coefficients = Matrixd<6, 4>::Zero(); + Eigen::Matrix m_coefficients = + Eigen::Matrix::Zero(); ControlVector m_initialControlVector; ControlVector m_finalControlVector; @@ -110,4 +115,5 @@ class TRAJOPT_DLLEXPORT CubicHermiteSpline : public Spline<3> { finalVector[1]}; } }; + } // namespace frc diff --git a/trajoptlib/include/trajopt/spline/EigenCore.hpp b/trajoptlib/include/trajopt/spline/EigenCore.hpp deleted file mode 100644 index 3a12a7d3c..000000000 --- a/trajoptlib/include/trajopt/spline/EigenCore.hpp +++ /dev/null @@ -1,21 +0,0 @@ -// Copyright (c) TrajoptLib contributors - -#pragma once - -#include - -namespace frc { - -template -using Vectord = Eigen::Vector; - -template -using Matrixd = Eigen::Matrix; - -} // namespace frc diff --git a/trajoptlib/include/trajopt/spline/Spline.hpp b/trajoptlib/include/trajopt/spline/Spline.hpp index 1ca9e1f92..1db6ad691 100644 --- a/trajoptlib/include/trajopt/spline/Spline.hpp +++ b/trajoptlib/include/trajopt/spline/Spline.hpp @@ -5,8 +5,9 @@ #include #include +#include + #include "trajopt/geometry/Pose2.hpp" -#include "trajopt/spline/EigenCore.hpp" #include "trajopt/spline/array.hpp" namespace frc { @@ -46,7 +47,7 @@ class Spline { * @return The pose and curvature at that point. */ std::optional GetPoint(double t) const { - Vectord polynomialBases; + Eigen::Vector polynomialBases; // Populate the polynomial bases for (int i = 0; i <= Degree; i++) { @@ -55,7 +56,7 @@ class Spline { // This simply multiplies by the coefficients. We need to divide out t some // n number of times where n is the derivative we want to take. - Vectord<6> combined = Coefficients() * polynomialBases; + Eigen::Vector combined = Coefficients() * polynomialBases; double dx, dy, ddx, ddy; @@ -94,7 +95,7 @@ class Spline { * * @return The coefficients of the spline. */ - virtual Matrixd<6, Degree + 1> Coefficients() const = 0; + virtual Eigen::Matrix Coefficients() const = 0; /** * Returns the initial control vector that created this spline.