WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
TravelingSalesman.hpp
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 <algorithm>
8#include <functional>
9#include <random>
10#include <utility>
11#include <vector>
12
16#include "wpi/util/array.hpp"
17
18namespace wpi::math {
19
20/**
21 * Given a list of poses, this class finds the shortest possible route that
22 * visits each pose exactly once and returns to the origin pose.
23 *
24 * @see <a
25 * href="https://en.wikipedia.org/wiki/Travelling_salesman_problem">https://en.wikipedia.org/wiki/Travelling_salesman_problem</a>
26 */
28 public:
29 /**
30 * Constructs a traveling salesman problem solver with a cost function defined
31 * as the 2D distance between poses.
32 */
33 constexpr TravelingSalesman() = default;
34
35 /**
36 * Constructs a traveling salesman problem solver with a user-provided cost
37 * function.
38 *
39 * @param cost Function that returns the cost between two poses. The sum of
40 * the costs for every pair of poses is minimized.
41 */
42 explicit TravelingSalesman(std::function<double(Pose2d, Pose2d)> cost)
43 : m_cost{std::move(cost)} {}
44
45 /**
46 * Finds the path through every pose that minimizes the cost. The first pose
47 * in the returned array is the first pose that was passed in.
48 *
49 * This overload supports a statically-sized list of poses.
50 *
51 * @tparam Poses The length of the path and the number of poses.
52 * @param poses An array of Pose2ds the path must pass through.
53 * @param iterations The number of times the solver attempts to find a better
54 * random neighbor.
55 * @return The optimized path as an array of Pose2ds.
56 */
57 template <size_t Poses>
59 const wpi::util::array<Pose2d, Poses>& poses, int iterations) {
61 1, &Neighbor<Poses>, [&](const Vectord<Poses>& state) {
62 // Total cost is sum of all costs between adjacent pairs in path
63 double sum = 0.0;
64 for (int i = 0; i < state.rows(); ++i) {
65 sum +=
66 m_cost(poses[static_cast<int>(state(i))],
67 poses[static_cast<int>(state((i + 1) % poses.size()))]);
68 }
69 return sum;
70 }};
71
72 Eigen::Vector<double, Poses> initial;
73 for (int i = 0; i < initial.rows(); ++i) {
74 initial(i) = i;
75 }
76
77 auto indices = solver.Solve(initial, iterations);
78
80 for (size_t i = 0; i < poses.size(); ++i) {
81 solution[i] = poses[static_cast<int>(indices[i])];
82 }
83
84 // Rotate solution list until solution[0] = poses[0]
85 std::rotate(solution.begin(),
86 std::find(solution.begin(), solution.end(), poses[0]),
87 solution.end());
88
89 return solution;
90 }
91
92 /**
93 * Finds the path through every pose that minimizes the cost. The first pose
94 * in the returned array is the first pose that was passed in.
95 *
96 * This overload supports a dynamically-sized list of poses for Python to use.
97 *
98 * @param poses An array of Pose2ds the path must pass through.
99 * @param iterations The number of times the solver attempts to find a better
100 * random neighbor.
101 * @return The optimized path as an array of Pose2ds.
102 */
103 std::vector<Pose2d> Solve(std::span<const Pose2d> poses, int iterations) {
105 1.0, &Neighbor<Eigen::Dynamic>, [&](const Eigen::VectorXd& state) {
106 // Total cost is sum of all costs between adjacent pairs in path
107 double sum = 0.0;
108 for (int i = 0; i < state.rows(); ++i) {
109 sum +=
110 m_cost(poses[static_cast<int>(state(i))],
111 poses[static_cast<int>(state((i + 1) % poses.size()))]);
112 }
113 return sum;
114 }};
115
116 Eigen::VectorXd initial{poses.size()};
117 for (int i = 0; i < initial.rows(); ++i) {
118 initial(i) = i;
119 }
120
121 auto indices = solver.Solve(initial, iterations);
122
123 std::vector<Pose2d> solution;
124 for (size_t i = 0; i < poses.size(); ++i) {
125 solution.emplace_back(poses[static_cast<int>(indices[i])]);
126 }
127
128 // Rotate solution list until solution[0] = poses[0]
129 std::rotate(solution.begin(),
130 std::find(solution.begin(), solution.end(), poses[0]),
131 solution.end());
132
133 return solution;
134 }
135
136 private:
137 // Default cost is distance between poses
138 std::function<double(const Pose2d&, const Pose2d&)> m_cost =
139 [](const Pose2d& a, const Pose2d& b) -> double {
140 return wpi::units::math::hypot(a.X() - b.X(), a.Y() - b.Y()).value();
141 };
142
143 /**
144 * A random neighbor is generated to try to replace the current one.
145 *
146 * @tparam Poses The length of the path and the number of poses.
147 * @param state A vector that is a list of indices that defines the path
148 * through the path array.
149 * @return Generates a random neighbor of the current state by flipping a
150 * random range in the path array.
151 */
152 template <int Poses>
153 static Eigen::Vector<double, Poses> Neighbor(
154 const Eigen::Vector<double, Poses>& state) {
155 Eigen::Vector<double, Poses> proposedState = state;
156
157 std::random_device rd;
158 std::mt19937 gen{rd()};
159 std::uniform_int_distribution<> distr{0,
160 static_cast<int>(state.rows()) - 1};
161
162 int rangeStart = distr(gen);
163 int rangeEnd = distr(gen);
164 if (rangeEnd < rangeStart) {
165 std::swap(rangeStart, rangeEnd);
166 }
167
168 for (int i = rangeStart; i <= (rangeStart + rangeEnd) / 2; ++i) {
169 double temp = proposedState(i, 0);
170 proposedState(i, 0) = state(rangeEnd - (i - rangeStart), 0);
171 proposedState(rangeEnd - (i - rangeStart), 0) = temp;
172 }
173
174 return proposedState;
175 }
176};
177
178} // namespace wpi::math
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
constexpr wpi::units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.hpp:114
constexpr wpi::units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose2d.hpp:121
An implementation of the Simulated Annealing stochastic nonlinear optimization method.
Definition SimulatedAnnealing.hpp:30
State Solve(const State &initialGuess, int iterations)
Runs the Simulated Annealing algorithm.
Definition SimulatedAnnealing.hpp:57
wpi::util::array< Pose2d, Poses > Solve(const wpi::util::array< Pose2d, Poses > &poses, int iterations)
Finds the path through every pose that minimizes the cost.
Definition TravelingSalesman.hpp:58
TravelingSalesman(std::function< double(Pose2d, Pose2d)> cost)
Constructs a traveling salesman problem solver with a user-provided cost function.
Definition TravelingSalesman.hpp:42
constexpr TravelingSalesman()=default
Constructs a traveling salesman problem solver with a cost function defined as the 2D distance betwee...
std::vector< Pose2d > Solve(std::span< const Pose2d > poses, int iterations)
Finds the path through every pose that minimizes the cost.
Definition TravelingSalesman.hpp:103
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
state
Definition base.h:1467
Definition StringMap.hpp:773
void swap(wpi::util::StringMap< T > &lhs, wpi::util::StringMap< T > &rhs)
Definition StringMap.hpp:775
Definition LinearSystem.hpp:20
Eigen::Vector< double, Size > Vectord
Definition EigenCore.hpp:12
constexpr empty_array_t empty_array
Definition array.hpp:16