mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath, wpiutil] Add wpi::array for compile time size checking (#3087)
The wpimath APIs use std::array, which doesn't do size checking. Passing an array with the wrong size can result in uninitialized elements instead of a compilation error. This is a breaking change but is worthwhile to avoid hard-to-debug errors.
This commit is contained in:
@@ -7,10 +7,10 @@
|
||||
using namespace frc;
|
||||
|
||||
CubicHermiteSpline::CubicHermiteSpline(
|
||||
std::array<double, 2> xInitialControlVector,
|
||||
std::array<double, 2> xFinalControlVector,
|
||||
std::array<double, 2> yInitialControlVector,
|
||||
std::array<double, 2> yFinalControlVector) {
|
||||
wpi::array<double, 2> xInitialControlVector,
|
||||
wpi::array<double, 2> xFinalControlVector,
|
||||
wpi::array<double, 2> yInitialControlVector,
|
||||
wpi::array<double, 2> yFinalControlVector) {
|
||||
const auto hermite = MakeHermiteBasis();
|
||||
const auto x =
|
||||
ControlVectorFromArrays(xInitialControlVector, xFinalControlVector);
|
||||
|
||||
@@ -7,10 +7,10 @@
|
||||
using namespace frc;
|
||||
|
||||
QuinticHermiteSpline::QuinticHermiteSpline(
|
||||
std::array<double, 3> xInitialControlVector,
|
||||
std::array<double, 3> xFinalControlVector,
|
||||
std::array<double, 3> yInitialControlVector,
|
||||
std::array<double, 3> yFinalControlVector) {
|
||||
wpi::array<double, 3> xInitialControlVector,
|
||||
wpi::array<double, 3> xFinalControlVector,
|
||||
wpi::array<double, 3> yInitialControlVector,
|
||||
wpi::array<double, 3> yFinalControlVector) {
|
||||
const auto hermite = MakeHermiteBasis();
|
||||
const auto x =
|
||||
ControlVectorFromArrays(xInitialControlVector, xFinalControlVector);
|
||||
|
||||
@@ -13,10 +13,10 @@ std::vector<CubicHermiteSpline> SplineHelper::CubicSplinesFromControlVectors(
|
||||
const Spline<3>::ControlVector& end) {
|
||||
std::vector<CubicHermiteSpline> splines;
|
||||
|
||||
std::array<double, 2> xInitial = start.x;
|
||||
std::array<double, 2> yInitial = start.y;
|
||||
std::array<double, 2> xFinal = end.x;
|
||||
std::array<double, 2> yFinal = end.y;
|
||||
wpi::array<double, 2> xInitial = start.x;
|
||||
wpi::array<double, 2> yInitial = start.y;
|
||||
wpi::array<double, 2> xFinal = end.x;
|
||||
wpi::array<double, 2> yFinal = end.y;
|
||||
|
||||
if (waypoints.size() > 1) {
|
||||
waypoints.emplace(waypoints.begin(),
|
||||
@@ -102,9 +102,9 @@ std::vector<CubicHermiteSpline> SplineHelper::CubicSplinesFromControlVectors(
|
||||
const double yDeriv =
|
||||
(3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0;
|
||||
|
||||
std::array<double, 2> midXControlVector{waypoints[0].X().to<double>(),
|
||||
wpi::array<double, 2> midXControlVector{waypoints[0].X().to<double>(),
|
||||
xDeriv};
|
||||
std::array<double, 2> midYControlVector{waypoints[0].Y().to<double>(),
|
||||
wpi::array<double, 2> midYControlVector{waypoints[0].Y().to<double>(),
|
||||
yDeriv};
|
||||
|
||||
splines.emplace_back(xInitial, midXControlVector, yInitial,
|
||||
@@ -134,7 +134,7 @@ SplineHelper::QuinticSplinesFromControlVectors(
|
||||
return splines;
|
||||
}
|
||||
|
||||
std::array<Spline<3>::ControlVector, 2>
|
||||
wpi::array<Spline<3>::ControlVector, 2>
|
||||
SplineHelper::CubicControlVectorsFromWaypoints(
|
||||
const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
|
||||
const Pose2d& end) {
|
||||
|
||||
Reference in New Issue
Block a user