Program Listing for File SPARStwo.h
↰ Return to documentation for file (src/ompl/geometric/planners/prm/SPARStwo.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, Rutgers the State University of New Jersey, New Brunswick
* All Rights Reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Rutgers University nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Andrew Dobson */
#ifndef OMPL_GEOMETRIC_PLANNERS_SPARS_TWO_
#define OMPL_GEOMETRIC_PLANNERS_SPARS_TWO_
#include "ompl/geometric/planners/PlannerIncludes.h"
#include "ompl/datastructures/NearestNeighbors.h"
#include "ompl/geometric/PathSimplifier.h"
#include "ompl/util/Time.h"
#include "ompl/util/Hash.h"
#include <boost/range/adaptor/map.hpp>
#include <unordered_map>
#include <boost/graph/graph_traits.hpp>
#include <boost/graph/adjacency_list.hpp>
#include <boost/pending/disjoint_sets.hpp>
#include <mutex>
#include <iostream>
#include <fstream>
#include <utility>
#include <vector>
#include <map>
namespace ompl
{
namespace geometric
{
class SPARStwo : public base::Planner
{
public:
enum GuardType
{
START,
GOAL,
COVERAGE,
CONNECTIVITY,
INTERFACE,
QUALITY,
};
using VertexIndexType = unsigned long;
using VertexPair = std::pair<VertexIndexType, VertexIndexType>;
struct InterfaceData
{
base::State *pointA_{nullptr};
base::State *pointB_{nullptr};
base::State *sigmaA_{nullptr};
base::State *sigmaB_{nullptr};
double d_{std::numeric_limits<double>::infinity()};
InterfaceData() = default;
void clear(const base::SpaceInformationPtr &si)
{
if (pointA_ != nullptr)
{
si->freeState(pointA_);
pointA_ = nullptr;
}
if (pointB_ != nullptr)
{
si->freeState(pointB_);
pointB_ = nullptr;
}
if (sigmaA_ != nullptr)
{
si->freeState(sigmaA_);
sigmaA_ = nullptr;
}
if (sigmaB_ != nullptr)
{
si->freeState(sigmaB_);
sigmaB_ = nullptr;
}
d_ = std::numeric_limits<double>::infinity();
}
void setFirst(const base::State *p, const base::State *s, const base::SpaceInformationPtr &si)
{
if (pointA_ != nullptr)
si->copyState(pointA_, p);
else
pointA_ = si->cloneState(p);
if (sigmaA_ != nullptr)
si->copyState(sigmaA_, s);
else
sigmaA_ = si->cloneState(s);
if (pointB_ != nullptr)
d_ = si->distance(pointA_, pointB_);
}
void setSecond(const base::State *p, const base::State *s, const base::SpaceInformationPtr &si)
{
if (pointB_ != nullptr)
si->copyState(pointB_, p);
else
pointB_ = si->cloneState(p);
if (sigmaB_ != nullptr)
si->copyState(sigmaB_, s);
else
sigmaB_ = si->cloneState(s);
if (pointA_ != nullptr)
d_ = si->distance(pointA_, pointB_);
}
};
using InterfaceHash = std::unordered_map<VertexPair, InterfaceData>;
struct vertex_state_t
{
using kind = boost::vertex_property_tag;
};
struct vertex_color_t
{
using kind = boost::vertex_property_tag;
};
struct vertex_interface_data_t
{
using kind = boost::vertex_property_tag;
};
using Graph = boost::adjacency_list<
boost::vecS, boost::vecS, boost::undirectedS,
boost::property<
vertex_state_t, base::State *,
boost::property<
boost::vertex_predecessor_t, VertexIndexType,
boost::property<boost::vertex_rank_t, VertexIndexType,
boost::property<vertex_color_t, GuardType,
boost::property<vertex_interface_data_t, InterfaceHash>>>>>,
boost::property<boost::edge_weight_t, base::Cost>>;
using Vertex = boost::graph_traits<Graph>::vertex_descriptor;
using Edge = boost::graph_traits<Graph>::edge_descriptor;
SPARStwo(const base::SpaceInformationPtr &si);
~SPARStwo() override;
void setProblemDefinition(const base::ProblemDefinitionPtr &pdef) override;
void setStretchFactor(double t)
{
stretchFactor_ = t;
}
void setSparseDeltaFraction(double D)
{
sparseDeltaFraction_ = D;
if (sparseDelta_ > 0.0) // setup was previously called
sparseDelta_ = D * si_->getMaximumExtent();
}
void setDenseDeltaFraction(double d)
{
denseDeltaFraction_ = d;
if (denseDelta_ > 0.0) // setup was previously called
denseDelta_ = d * si_->getMaximumExtent();
}
void setMaxFailures(unsigned int m)
{
maxFailures_ = m;
}
unsigned int getMaxFailures() const
{
return maxFailures_;
}
double getDenseDeltaFraction() const
{
return denseDeltaFraction_;
}
double getSparseDeltaFraction() const
{
return sparseDeltaFraction_;
}
double getStretchFactor() const
{
return stretchFactor_;
}
void constructRoadmap(const base::PlannerTerminationCondition &ptc);
void constructRoadmap(const base::PlannerTerminationCondition &ptc, bool stopOnMaxFail);
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
void clearQuery() override;
void clear() override;
template <template <typename T> class NN>
void setNearestNeighbors()
{
if (nn_ && nn_->size() == 0)
OMPL_WARN("Calling setNearestNeighbors will clear all states.");
clear();
nn_ = std::make_shared<NN<Vertex>>();
if (isSetup())
setup();
}
void setup() override;
const Graph &getRoadmap() const
{
return g_;
}
unsigned int milestoneCount() const
{
return boost::num_vertices(g_);
}
void getPlannerData(base::PlannerData &data) const override;
void printDebug(std::ostream &out = std::cout) const;
// Planner progress property functions
std::string getIterationCount() const
{
return std::to_string(iterations_);
}
std::string getBestCost() const
{
return std::to_string(bestCost_.value());
}
protected:
void freeMemory();
void checkQueryStateInitialization();
bool checkAddCoverage(const base::State *qNew, std::vector<Vertex> &visibleNeighborhood);
bool checkAddConnectivity(const base::State *qNew, std::vector<Vertex> &visibleNeighborhood);
bool checkAddInterface(const base::State *qNew, std::vector<Vertex> &graphNeighborhood,
std::vector<Vertex> &visibleNeighborhood);
bool checkAddPath(Vertex v);
void resetFailures();
void findGraphNeighbors(base::State *st, std::vector<Vertex> &graphNeighborhood,
std::vector<Vertex> &visibleNeighborhood);
void approachGraph(Vertex v);
Vertex findGraphRepresentative(base::State *st);
void findCloseRepresentatives(base::State *workArea, const base::State *qNew, Vertex qRep,
std::map<Vertex, base::State *> &closeRepresentatives,
const base::PlannerTerminationCondition &ptc);
void updatePairPoints(Vertex rep, const base::State *q, Vertex r, const base::State *s);
void computeVPP(Vertex v, Vertex vp, std::vector<Vertex> &VPPs);
void computeX(Vertex v, Vertex vp, Vertex vpp, std::vector<Vertex> &Xs);
VertexPair index(Vertex vp, Vertex vpp);
InterfaceData &getData(Vertex v, Vertex vp, Vertex vpp);
void distanceCheck(Vertex rep, const base::State *q, Vertex r, const base::State *s, Vertex rp);
void abandonLists(base::State *st);
Vertex addGuard(base::State *state, GuardType type);
void connectGuards(Vertex v, Vertex vp);
bool haveSolution(const std::vector<Vertex> &starts, const std::vector<Vertex> &goals,
base::PathPtr &solution);
void checkForSolution(const base::PlannerTerminationCondition &ptc, base::PathPtr &solution);
bool reachedTerminationCriterion() const;
bool reachedFailureLimit() const;
base::PathPtr constructSolution(Vertex start, Vertex goal) const;
bool sameComponent(Vertex m1, Vertex m2);
double distanceFunction(const Vertex a, const Vertex b) const
{
return si_->distance(stateProperty_[a], stateProperty_[b]);
}
base::ValidStateSamplerPtr sampler_;
std::shared_ptr<NearestNeighbors<Vertex>> nn_;
Graph g_;
std::vector<Vertex> startM_;
std::vector<Vertex> goalM_;
Vertex queryVertex_;
double stretchFactor_{3.};
double sparseDeltaFraction_{.25};
double denseDeltaFraction_{.001};
unsigned int maxFailures_{5000};
unsigned int nearSamplePoints_;
boost::property_map<Graph, vertex_state_t>::type stateProperty_;
PathSimplifierPtr psimp_;
boost::property_map<Graph, boost::edge_weight_t>::type weightProperty_;
boost::property_map<Graph, vertex_color_t>::type colorProperty_;
boost::property_map<Graph, vertex_interface_data_t>::type interfaceDataProperty_;
boost::disjoint_sets<boost::property_map<Graph, boost::vertex_rank_t>::type,
boost::property_map<Graph, boost::vertex_predecessor_t>::type> disjointSets_;
RNG rng_;
bool addedSolution_{false};
unsigned int consecutiveFailures_{0};
double sparseDelta_{0.};
double denseDelta_{0.};
mutable std::mutex graphMutex_;
base::OptimizationObjectivePtr opt_;
base::Cost costHeuristic(Vertex u, Vertex v) const;
// Planner progress properties
long unsigned int iterations_{0ul};
base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
};
}
}
#endif