forked from wpilibsuite/allwpilib
-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Co-authored-by: Ashray._.g <ashray.gupta@gmail.com>
- Loading branch information
Showing
8 changed files
with
718 additions
and
0 deletions.
There are no files selected for viewing
78 changes: 78 additions & 0 deletions
78
wpimath/src/main/java/edu/wpi/first/math/optimization/SimulatedAnnealing.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 <a | ||
* href="https://en.wikipedia.org/wiki/Simulated_annealing">https://en.wikipedia.org/wiki/Simulated_annealing</a> | ||
*/ | ||
public final class SimulatedAnnealing<T> { | ||
private final double m_initialTemperature; | ||
private final Function<T, T> m_neighbor; | ||
private final ToDoubleFunction<T> 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<T, T> neighbor, ToDoubleFunction<T> 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; | ||
} | ||
} |
110 changes: 110 additions & 0 deletions
110
wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 <a | ||
* href="https://en.wikipedia.org/wiki/Travelling_salesman_problem">https://en.wikipedia.org/wiki/Travelling_salesman_problem</a> | ||
*/ | ||
public class TravelingSalesman { | ||
// Default cost is 2D distance between poses | ||
private final ToDoubleBiFunction<Pose2d, Pose2d> 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<Pose2d, Pose2d> cost) { | ||
m_cost = cost; | ||
} | ||
|
||
/** | ||
* Finds the path through every pose that minimizes the cost. | ||
* | ||
* @param <Poses> 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 <Poses extends Num> 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<Poses> 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>(() -> 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 <Poses extends Num> Vector<Poses> neighbor(Vector<Poses> state) { | ||
var proposedState = new Vector<Poses>(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; | ||
} | ||
} |
93 changes: 93 additions & 0 deletions
93
wpimath/src/main/native/include/frc/optimization/SimulatedAnnealing.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 <cmath> | ||
#include <functional> | ||
#include <limits> | ||
#include <random> | ||
|
||
namespace frc { | ||
|
||
/** | ||
* An implementation of the Simulated Annealing stochastic nonlinear | ||
* optimization method. | ||
* | ||
* @see <a | ||
* href="https://en.wikipedia.org/wiki/Simulated_annealing">https://en.wikipedia.org/wiki/Simulated_annealing</a> | ||
*/ | ||
template <typename T> | ||
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<T(const T&)> neighbor, | ||
std::function<double(const T&)> 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<double>::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<T(const T&)> m_neighbor; | ||
std::function<double(const T&)> m_cost; | ||
}; | ||
|
||
} // namespace frc |
Oops, something went wrong.