Skip to content

Commit

Permalink
Remove Eigen shim header
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul committed Jan 4, 2025
1 parent 60f79dd commit 98d61e2
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 28 deletions.
12 changes: 9 additions & 3 deletions trajoptlib/include/trajopt/spline/CubicHermiteSpline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,14 @@

#pragma once

#include "trajopt/spline/EigenCore.hpp"
#include <Eigen/Core>

#include "trajopt/spline/Spline.hpp"
#include "trajopt/spline/array.hpp"
#include "trajopt/util/SymbolExports.hpp"

namespace frc {

/**
* Represents a hermite spline of degree 3.
*/
Expand Down Expand Up @@ -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<double, 6, 3 + 1> Coefficients() const override {
return m_coefficients;
}

/**
* Returns the initial control vector that created this spline.
Expand All @@ -57,7 +61,8 @@ class TRAJOPT_DLLEXPORT CubicHermiteSpline : public Spline<3> {
}

private:
Matrixd<6, 4> m_coefficients = Matrixd<6, 4>::Zero();
Eigen::Matrix<double, 6, 4> m_coefficients =
Eigen::Matrix<double, 6, 4>::Zero();

ControlVector m_initialControlVector;
ControlVector m_finalControlVector;
Expand Down Expand Up @@ -110,4 +115,5 @@ class TRAJOPT_DLLEXPORT CubicHermiteSpline : public Spline<3> {
finalVector[1]};
}
};

} // namespace frc
21 changes: 0 additions & 21 deletions trajoptlib/include/trajopt/spline/EigenCore.hpp

This file was deleted.

9 changes: 5 additions & 4 deletions trajoptlib/include/trajopt/spline/Spline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,9 @@
#include <optional>
#include <utility>

#include <Eigen/Core>

#include "trajopt/geometry/Pose2.hpp"
#include "trajopt/spline/EigenCore.hpp"
#include "trajopt/spline/array.hpp"

namespace frc {
Expand Down Expand Up @@ -46,7 +47,7 @@ class Spline {
* @return The pose and curvature at that point.
*/
std::optional<PoseWithCurvature> GetPoint(double t) const {
Vectord<Degree + 1> polynomialBases;
Eigen::Vector<double, Degree + 1> polynomialBases;

// Populate the polynomial bases
for (int i = 0; i <= Degree; i++) {
Expand All @@ -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<double, 6> combined = Coefficients() * polynomialBases;

double dx, dy, ddx, ddy;

Expand Down Expand Up @@ -94,7 +95,7 @@ class Spline {
*
* @return The coefficients of the spline.
*/
virtual Matrixd<6, Degree + 1> Coefficients() const = 0;
virtual Eigen::Matrix<double, 6, Degree + 1> Coefficients() const = 0;

/**
* Returns the initial control vector that created this spline.
Expand Down

0 comments on commit 98d61e2

Please sign in to comment.