diff --git a/wpimath/src/main/java/edu/wpi/first/math/optimization/SimulatedAnnealing.java b/wpimath/src/main/java/edu/wpi/first/math/optimization/SimulatedAnnealing.java
new file mode 100644
index 00000000000..bf75e1dec9e
--- /dev/null
+++ b/wpimath/src/main/java/edu/wpi/first/math/optimization/SimulatedAnnealing.java
@@ -0,0 +1,78 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.optimization;
+
+import java.util.function.Function;
+import java.util.function.ToDoubleFunction;
+
+/**
+ * An implementation of the Simulated Annealing stochastic nonlinear optimization method.
+ *
+ * @see https://en.wikipedia.org/wiki/Simulated_annealing
+ */
+public final class SimulatedAnnealing {
+ private final double m_initialTemperature;
+ private final Function m_neighbor;
+ private final ToDoubleFunction m_cost;
+
+ /**
+ * Constructor for Simulated Annealing that can be used for the same functions but with different
+ * initial states.
+ *
+ * @param initialTemperature The initial temperature. Higher temperatures make it more likely a
+ * worse state will be accepted during iteration, helping to avoid local minima. The
+ * temperature is decreased over time.
+ * @param neighbor Function that generates a random neighbor of the current state vector.
+ * @param cost Function that returns the scalar cost of a state vector.
+ */
+ public SimulatedAnnealing(
+ double initialTemperature, Function neighbor, ToDoubleFunction cost) {
+ m_initialTemperature = initialTemperature;
+ m_neighbor = neighbor;
+ m_cost = cost;
+ }
+
+ /**
+ * Runs the Simulated Annealing algorithm.
+ *
+ * @param initialGuess The initial state.
+ * @param iterations Number of iterations to run the solver.
+ * @return The optimized state vector.
+ */
+ public T solve(T initialGuess, int iterations) {
+ T minState = initialGuess;
+ double minCost = Double.MAX_VALUE;
+
+ T state = initialGuess;
+ double cost = m_cost.applyAsDouble(state);
+
+ for (int i = 0; i < iterations; ++i) {
+ double temperature = m_initialTemperature / i;
+
+ T proposedState = m_neighbor.apply(state);
+ double proposedCost = m_cost.applyAsDouble(proposedState);
+ double deltaCost = proposedCost - cost;
+
+ double acceptanceProbability = Math.exp(-deltaCost / temperature);
+
+ // If cost went down or random number exceeded acceptance probability,
+ // accept the proposed state
+ if (deltaCost < 0 || acceptanceProbability >= Math.random()) {
+ state = proposedState;
+ cost = proposedCost;
+ }
+
+ // If proposed cost is less than minimum, the proposed state becomes the
+ // new minimum
+ if (proposedCost < minCost) {
+ minState = proposedState;
+ minCost = proposedCost;
+ }
+ }
+
+ return minState;
+ }
+}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java b/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java
new file mode 100644
index 00000000000..be4f99928c5
--- /dev/null
+++ b/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java
@@ -0,0 +1,110 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.path;
+
+import edu.wpi.first.math.Num;
+import edu.wpi.first.math.Vector;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.optimization.SimulatedAnnealing;
+import java.util.function.ToDoubleBiFunction;
+
+/**
+ * Given a list of poses, this class finds the shortest possible route that visits each pose exactly
+ * once and returns to the origin pose.
+ *
+ * @see https://en.wikipedia.org/wiki/Travelling_salesman_problem
+ */
+public class TravelingSalesman {
+ // Default cost is 2D distance between poses
+ private final ToDoubleBiFunction m_cost;
+
+ /**
+ * Constructs a traveling salesman problem solver with a cost function defined as the 2D distance
+ * between poses.
+ */
+ public TravelingSalesman() {
+ this((Pose2d a, Pose2d b) -> Math.hypot(a.getX() - b.getX(), a.getY() - b.getY()));
+ }
+
+ /**
+ * Constructs a traveling salesman problem solver with a user-provided cost function.
+ *
+ * @param cost Function that returns the cost between two poses. The sum of the costs for every
+ * pair of poses is minimized.
+ */
+ public TravelingSalesman(ToDoubleBiFunction cost) {
+ m_cost = cost;
+ }
+
+ /**
+ * Finds the path through every pose that minimizes the cost.
+ *
+ * @param A Num defining the length of the path and the number of poses.
+ * @param poses An array of Pose2ds the path must pass through.
+ * @param iterations The number of times the solver attempts to find a better random neighbor.
+ * @return The optimized path as a list of Pose2ds.
+ */
+ public Pose2d[] solve(Pose2d[] poses, int iterations) {
+ var solver =
+ new SimulatedAnnealing<>(
+ 1,
+ this::neighbor,
+ // Total cost is sum of all costs between adjacent pose pairs in path
+ (Vector state) -> {
+ double sum = 0;
+ for (int i = 0; i < state.getNumRows(); ++i) {
+ sum +=
+ m_cost.applyAsDouble(
+ poses[(int) state.get(i, 0)],
+ poses[(int) (state.get((i + 1) % poses.length, 0))]);
+ }
+ return sum;
+ });
+
+ var initial = new Vector(() -> poses.length);
+ for (int i = 0; i < poses.length; ++i) {
+ initial.set(i, 0, i);
+ }
+
+ var indices = solver.solve(initial, iterations);
+
+ var solution = new Pose2d[poses.length];
+ int dest = 0;
+ for (int src = 0; src < indices.getNumRows(); ++src) {
+ solution[dest] = poses[(int) indices.get(src, 0)];
+ ++dest;
+ }
+
+ return solution;
+ }
+
+ /**
+ * A random neighbor is generated to try to replace the current one.
+ *
+ * @param state A vector that is a list of indices that defines the path through the path array.
+ * @return Generates a random neighbor of the current state by flipping a random range in the path
+ * array.
+ */
+ private Vector neighbor(Vector state) {
+ var proposedState = new Vector(state);
+
+ int rangeStart = (int) (Math.random() * (state.getNumRows() - 1));
+ int rangeEnd = (int) (Math.random() * (state.getNumRows() - 1));
+ if (rangeEnd < rangeStart) {
+ int temp = rangeEnd;
+ rangeEnd = rangeStart;
+ rangeStart = temp;
+ }
+
+ for (int i = rangeStart; i <= (rangeStart + rangeEnd) / 2; ++i) {
+ double temp = proposedState.get(i, 0);
+ proposedState.set(i, 0, state.get(rangeEnd - (i - rangeStart), 0));
+ proposedState.set(rangeEnd - (i - rangeStart), 0, temp);
+ }
+
+ return proposedState;
+ }
+}
diff --git a/wpimath/src/main/native/include/frc/optimization/SimulatedAnnealing.h b/wpimath/src/main/native/include/frc/optimization/SimulatedAnnealing.h
new file mode 100644
index 00000000000..8bac444f24d
--- /dev/null
+++ b/wpimath/src/main/native/include/frc/optimization/SimulatedAnnealing.h
@@ -0,0 +1,93 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include
+#include
+#include
+#include
+
+namespace frc {
+
+/**
+ * An implementation of the Simulated Annealing stochastic nonlinear
+ * optimization method.
+ *
+ * @see https://en.wikipedia.org/wiki/Simulated_annealing
+ */
+template
+class SimulatedAnnealing {
+ public:
+ /**
+ * Constructor for Simulated Annealing that can be used for the same functions
+ * but with different initial states.
+ *
+ * @param initialTemperature The initial temperature. Higher temperatures make
+ * it more likely a worse state will be accepted during iteration, helping
+ * to avoid local minima. The temperature is decreased over time.
+ * @param neighbor Function that generates a random neighbor of the current
+ * state vector.
+ * @param cost Function that returns the scalar cost of a state vector.
+ */
+ SimulatedAnnealing(double initialTemperature,
+ std::function neighbor,
+ std::function cost)
+ : m_initialTemperature{initialTemperature},
+ m_neighbor{neighbor},
+ m_cost{cost} {}
+
+ /**
+ * Runs the Simulated Annealing algorithm.
+ *
+ * @param initialGuess The initial state.
+ * @param iterations Number of iterations to run the solver.
+ * @return The optimized state vector.
+ */
+ T Solve(const T& initialGuess, int iterations) {
+ T minState = initialGuess;
+ double minCost = std::numeric_limits::infinity();
+
+ std::random_device rd;
+ std::mt19937 gen{rd()};
+ std::uniform_real_distribution<> distr{0.0, 1.0};
+
+ T state = initialGuess;
+ double cost = m_cost(state);
+
+ for (int i = 0; i < iterations; ++i) {
+ double temperature = m_initialTemperature / i;
+
+ T proposedState = m_neighbor(state);
+ double proposedCost = m_cost(proposedState);
+ double deltaCost = proposedCost - cost;
+
+ double acceptanceProbability = std::exp(-deltaCost / temperature);
+
+ // If cost went down or random number exceeded acceptance probability,
+ // accept the proposed state
+ if (deltaCost < 0 || acceptanceProbability >= distr(gen)) {
+ state = proposedState;
+ cost = proposedCost;
+ }
+
+ // If proposed cost is less than minimum, the proposed state becomes the
+ // new minimum
+ if (proposedCost < minCost) {
+ minState = proposedState;
+ minCost = proposedCost;
+ }
+ }
+
+ return minState;
+ }
+
+ private:
+ double m_initialTemperature;
+ std::function m_neighbor;
+ std::function m_cost;
+};
+
+} // namespace frc
diff --git a/wpimath/src/main/native/include/frc/path/TravelingSalesman.h b/wpimath/src/main/native/include/frc/path/TravelingSalesman.h
new file mode 100644
index 00000000000..2808853d87d
--- /dev/null
+++ b/wpimath/src/main/native/include/frc/path/TravelingSalesman.h
@@ -0,0 +1,126 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+
+#include
+#include
+#include
+#include
+
+#include
+
+#include "frc/EigenCore.h"
+#include "frc/geometry/Pose2d.h"
+#include "frc/optimization/SimulatedAnnealing.h"
+
+namespace frc {
+
+/**
+ * Given a list of poses, this class finds the shortest possible route that
+ * visits each pose exactly once and returns to the origin pose.
+ *
+ * @see https://en.wikipedia.org/wiki/Travelling_salesman_problem
+ */
+class TravelingSalesman {
+ public:
+ /**
+ * Constructs a traveling salesman problem solver with a cost function defined
+ * as the 2D distance between poses.
+ */
+ TravelingSalesman() = default;
+
+ /**
+ * Constructs a traveling salesman problem solver with a user-provided cost
+ * function.
+ *
+ * @param cost Function that returns the cost between two poses. The sum of
+ * the costs for every pair of poses is minimized.
+ */
+ explicit TravelingSalesman(std::function cost)
+ : m_cost{std::move(cost)} {}
+
+ /**
+ * Finds the path through every pose that minimizes the cost.
+ *
+ * @tparam Poses The length of the path and the number of poses.
+ * @param poses An array of Pose2ds the path must pass through.
+ * @param iterations The number of times the solver attempts to find a better
+ * random neighbor.
+ * @return The optimized path as a list of Pose2ds.
+ */
+ template
+ wpi::array Solve(const wpi::array& poses,
+ int iterations) {
+ SimulatedAnnealing> solver{
+ 1, &Neighbor, [&](const Vectord& state) {
+ // Total cost is sum of all costs between adjacent pairs in path
+ double sum = 0;
+ for (int i = 0; i < state.rows(); ++i) {
+ sum += m_cost(poses[static_cast(state(i))],
+ poses[static_cast(state((i + 1) % Poses))]);
+ }
+ return sum;
+ }};
+
+ Eigen::Vector initial;
+ for (int i = 0; i < initial.rows(); ++i) {
+ initial(i) = i;
+ }
+
+ auto indices = solver.Solve(initial, iterations);
+
+ wpi::array solution{wpi::empty_array};
+ int dest = 0;
+ for (const auto& src : indices) {
+ solution[dest] = poses[static_cast(src)];
+ ++dest;
+ }
+
+ return solution;
+ }
+
+ private:
+ // Default cost is distance between poses
+ std::function m_cost =
+ [](const Pose2d& a, const Pose2d& b) -> double {
+ return units::math::hypot(a.X() - b.X(), a.Y() - b.Y()).value();
+ };
+
+ /**
+ * A random neighbor is generated to try to replace the current one.
+ *
+ * @tparam Poses The length of the path and the number of poses.
+ * @param state A vector that is a list of indices that defines the path
+ * through the path array.
+ * @return Generates a random neighbor of the current state by flipping a
+ * random range in the path array.
+ */
+ template
+ static Eigen::Vector Neighbor(
+ const Eigen::Vector& state) {
+ Eigen::Vector proposedState = state;
+
+ std::random_device rd;
+ std::mt19937 gen{rd()};
+ std::uniform_int_distribution<> distr{0, Poses - 1};
+
+ int rangeStart = distr(gen);
+ int rangeEnd = distr(gen);
+ if (rangeEnd < rangeStart) {
+ std::swap(rangeStart, rangeEnd);
+ }
+
+ for (int i = rangeStart; i <= (rangeStart + rangeEnd) / 2; ++i) {
+ double temp = proposedState(i, 0);
+ proposedState(i, 0) = state(rangeEnd - (i - rangeStart), 0);
+ proposedState(rangeEnd - (i - rangeStart), 0) = temp;
+ }
+
+ return proposedState;
+ }
+};
+
+} // namespace frc
diff --git a/wpimath/src/test/java/edu/wpi/first/math/optimization/SimulatedAnnealingTest.java b/wpimath/src/test/java/edu/wpi/first/math/optimization/SimulatedAnnealingTest.java
new file mode 100644
index 00000000000..d051b4328d0
--- /dev/null
+++ b/wpimath/src/test/java/edu/wpi/first/math/optimization/SimulatedAnnealingTest.java
@@ -0,0 +1,47 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.optimization;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+import edu.wpi.first.math.MathUtil;
+import java.util.function.DoubleUnaryOperator;
+import org.junit.jupiter.api.Test;
+
+class SimulatedAnnealingTest {
+ @Test
+ void testDoubleFunctionOptimizationHeartBeat() {
+ DoubleUnaryOperator function = x -> -(x + Math.sin(x)) * Math.exp(-x * x) + 1;
+
+ double stepSize = 10.0;
+
+ var simulatedAnnealing =
+ new SimulatedAnnealing(
+ 2.0,
+ x -> MathUtil.clamp(x + (Math.random() - 0.5) * stepSize, -3, 3),
+ x -> function.applyAsDouble(x));
+
+ double solution = simulatedAnnealing.solve(-1.0, 5000);
+
+ assertEquals(0.68, solution, 1e-1);
+ }
+
+ @Test
+ void testDoubleFunctionOptimizationMultimodal() {
+ DoubleUnaryOperator function = x -> Math.sin(x) + Math.sin((10.0 / 3.0) * x);
+
+ double stepSize = 10.0;
+
+ var simulatedAnnealing =
+ new SimulatedAnnealing(
+ 2.0,
+ x -> MathUtil.clamp(x + (Math.random() - 0.5) * stepSize, 0, 7),
+ x -> function.applyAsDouble(x));
+
+ double solution = simulatedAnnealing.solve(-1.0, 5000);
+
+ assertEquals(5.146, solution, 1e-1);
+ }
+}
diff --git a/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java b/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java
new file mode 100644
index 00000000000..7b2e6951109
--- /dev/null
+++ b/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java
@@ -0,0 +1,109 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.math.path;
+
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.util.CircularBuffer;
+import org.junit.jupiter.api.Test;
+
+class TravelingSalesmanTest {
+ /**
+ * Returns true if the cycles represented by the two lists match.
+ *
+ * @param expected The expected cycle.
+ * @param actual The actual cycle.
+ */
+ private boolean isMatchingCycle(Pose2d[] expected, Pose2d[] actual) {
+ // Find first element in actual that matches expected
+ int actualStart = 0;
+ while (!actual[actualStart].equals(expected[0])) {
+ ++actualStart;
+ }
+
+ // Check actual has expected cycle (forward)
+ var actualBufferForward = new CircularBuffer(actual.length);
+ for (int i = 0; i < actual.length; ++i) {
+ actualBufferForward.addLast(actual[(actualStart + i) % actual.length]);
+ }
+ boolean matchesExpectedForward = true;
+ for (int i = 0; i < expected.length; ++i) {
+ matchesExpectedForward &= expected[i].equals(actualBufferForward.get(i));
+ }
+
+ // Check actual has expected cycle (reverse)
+ var actualBufferReverse = new CircularBuffer(actual.length);
+ for (int i = 0; i < actual.length; ++i) {
+ actualBufferReverse.addFirst(actual[(actualStart + 1 + i) % actual.length]);
+ }
+
+ boolean matchesExpectedReverse = true;
+ for (int i = 0; i < expected.length; ++i) {
+ matchesExpectedReverse &= expected[i].equals(actualBufferReverse.get(i));
+ }
+
+ // Actual may be reversed from expected, but that's still valid
+ return matchesExpectedForward || matchesExpectedReverse;
+ }
+
+ @Test
+ void testFiveLengthPathWithDistanceCost() {
+ // ...................
+ // ........2..........
+ // ..0..........4.....
+ // ...................
+ // ....3.....1........
+ // ...................
+ var poses =
+ new Pose2d[] {
+ new Pose2d(3, 3, new Rotation2d(0)),
+ new Pose2d(11, 5, new Rotation2d(0)),
+ new Pose2d(9, 2, new Rotation2d(0)),
+ new Pose2d(5, 5, new Rotation2d(0)),
+ new Pose2d(14, 3, new Rotation2d(0))
+ };
+
+ var traveler = new TravelingSalesman();
+ var solution = traveler.solve(poses, 500);
+
+ var expected = new Pose2d[] {poses[0], poses[2], poses[4], poses[1], poses[3]};
+ assertTrue(isMatchingCycle(expected, solution));
+ }
+
+ @Test
+ void testTenLengthPathWithDistanceCost() {
+ // ....6.3..1.2.......
+ // ..4................
+ // .............9.....
+ // .0.................
+ // .....7..5...8......
+ // ...................
+ var poses =
+ new Pose2d[] {
+ new Pose2d(2, 4, new Rotation2d(0)),
+ new Pose2d(10, 1, new Rotation2d(0)),
+ new Pose2d(12, 1, new Rotation2d(0)),
+ new Pose2d(7, 1, new Rotation2d(0)),
+ new Pose2d(3, 2, new Rotation2d(0)),
+ new Pose2d(9, 5, new Rotation2d(0)),
+ new Pose2d(5, 1, new Rotation2d(0)),
+ new Pose2d(6, 5, new Rotation2d(0)),
+ new Pose2d(13, 5, new Rotation2d(0)),
+ new Pose2d(14, 3, new Rotation2d(0))
+ };
+
+ var traveler = new TravelingSalesman();
+ var solution = traveler.solve(poses, 500);
+
+ var expected =
+ new Pose2d[] {
+ poses[0], poses[4], poses[6], poses[3], poses[1], poses[2], poses[9], poses[8], poses[5],
+ poses[7]
+ };
+ assertTrue(isMatchingCycle(expected, solution));
+ }
+}
diff --git a/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp b/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp
new file mode 100644
index 00000000000..5c7748a120d
--- /dev/null
+++ b/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp
@@ -0,0 +1,57 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include
+#include
+#include
+
+#include
+
+#include "frc/optimization/SimulatedAnnealing.h"
+
+TEST(SimulatedAnnealingTest, DoubleFunctionOptimizationHeartBeat) {
+ auto function = [](double x) {
+ return -(x + std::sin(x)) * std::exp(-x * x) + 1;
+ };
+
+ constexpr double stepSize = 10.0;
+
+ std::random_device rd;
+ std::mt19937 gen{rd()};
+ std::uniform_real_distribution<> distr{0.0, 1.0};
+
+ frc::SimulatedAnnealing simulatedAnnealing{
+ 2.0,
+ [&](const double& x) {
+ return std::clamp(x + (distr(gen) - 0.5) * stepSize, -3.0, 3.0);
+ },
+ [&](const double& x) { return function(x); }};
+
+ double solution = simulatedAnnealing.Solve(-1.0, 5000);
+
+ EXPECT_NEAR(0.68, solution, 1e-1);
+}
+
+TEST(SimulatedAnnealingTest, DoubleFunctionOptimizationMultimodal) {
+ auto function = [](double x) {
+ return std::sin(x) + std::sin((10.0 / 3.0) * x);
+ };
+
+ constexpr double stepSize = 10.0;
+
+ std::random_device rd;
+ std::mt19937 gen{rd()};
+ std::uniform_real_distribution<> distr{0.0, 1.0};
+
+ frc::SimulatedAnnealing simulatedAnnealing{
+ 2.0,
+ [&](const double& x) {
+ return std::clamp(x + (distr(gen) - 0.5) * stepSize, 0.0, 7.0);
+ },
+ [&](const double& x) { return function(x); }};
+
+ double solution = simulatedAnnealing.Solve(-1.0, 5000);
+
+ EXPECT_NEAR(5.146, solution, 1e-1);
+}
diff --git a/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp b/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp
new file mode 100644
index 00000000000..b3fbe7291b0
--- /dev/null
+++ b/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp
@@ -0,0 +1,98 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include
+#include
+#include
+
+#include "frc/EigenCore.h"
+#include "frc/geometry/Pose2d.h"
+#include "frc/geometry/Rotation2d.h"
+#include "frc/path/TravelingSalesman.h"
+
+/**
+ * Returns true if the cycles represented by the two lists match.
+ *
+ * @tparam Poses The length of the path and the number of poses.
+ * @param expected The expected cycle.
+ * @param actual The actual cycle.
+ */
+template
+bool IsMatchingCycle(const wpi::array& expected,
+ const wpi::array& actual) {
+ // Find first element in actual that matches expected
+ size_t actualStart = 0;
+ while (actual[actualStart] != expected[0]) {
+ ++actualStart;
+ }
+
+ // Check actual has expected cycle (forward)
+ wpi::static_circular_buffer actualBufferForward;
+ for (size_t i = 0; i < actual.size(); ++i) {
+ actualBufferForward.push_back(actual[(actualStart + i) % actual.size()]);
+ }
+ bool matchesExpectedForward = true;
+ for (size_t i = 0; i < expected.size(); ++i) {
+ matchesExpectedForward &= (expected[i] == actualBufferForward[i]);
+ }
+
+ // Check actual has expected cycle (reverse)
+ wpi::static_circular_buffer actualBufferReverse;
+ for (size_t i = 0; i < actual.size(); ++i) {
+ actualBufferReverse.push_front(
+ actual[(actualStart + 1 + i) % actual.size()]);
+ }
+ bool matchesExpectedReverse = true;
+ for (size_t i = 0; i < expected.size(); ++i) {
+ matchesExpectedReverse &= (expected[i] == actualBufferReverse[i]);
+ }
+
+ // Actual may be reversed from expected, but that's still valid
+ return matchesExpectedForward || matchesExpectedReverse;
+}
+
+TEST(TravelingSalesmanTest, FiveLengthPathWithDistanceCost) {
+ // ...................
+ // ........2..........
+ // ..0..........4.....
+ // ...................
+ // ....3.....1........
+ // ...................
+ wpi::array poses{
+ frc::Pose2d{3_m, 3_m, 0_rad}, frc::Pose2d{11_m, 5_m, 0_rad},
+ frc::Pose2d{9_m, 2_m, 0_rad}, frc::Pose2d{5_m, 5_m, 0_rad},
+ frc::Pose2d{14_m, 3_m, 0_rad}};
+
+ frc::TravelingSalesman traveler;
+ wpi::array solution = traveler.Solve(poses, 500);
+
+ wpi::array expected{poses[0], poses[2], poses[4], poses[1],
+ poses[3]};
+
+ EXPECT_TRUE(IsMatchingCycle(expected, solution));
+}
+
+TEST(TravelingSalesmanTest, TenLengthPathWithDistanceCost) {
+ // ....6.3..1.2.......
+ // ..4................
+ // .............9.....
+ // .0.................
+ // .....7..5...8......
+ // ...................
+ wpi::array poses{
+ frc::Pose2d{2_m, 4_m, 0_rad}, frc::Pose2d{10_m, 1_m, 0_rad},
+ frc::Pose2d{12_m, 1_m, 0_rad}, frc::Pose2d{7_m, 1_m, 0_rad},
+ frc::Pose2d{3_m, 2_m, 0_rad}, frc::Pose2d{9_m, 5_m, 0_rad},
+ frc::Pose2d{5_m, 1_m, 0_rad}, frc::Pose2d{6_m, 5_m, 0_rad},
+ frc::Pose2d{13_m, 5_m, 0_rad}, frc::Pose2d{14_m, 3_m, 0_rad}};
+
+ frc::TravelingSalesman traveler;
+ wpi::array solution = traveler.Solve(poses, 500);
+
+ wpi::array expected{poses[0], poses[4], poses[6], poses[3],
+ poses[1], poses[2], poses[9], poses[8],
+ poses[5], poses[7]};
+
+ EXPECT_TRUE(IsMatchingCycle(expected, solution));
+}