Program Listing for File SPARS.h
↰ Return to documentation for file (src/ompl/geometric/planners/prm/SPARS.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_SPARSE_ROADMAP_SPANNER_
#define OMPL_GEOMETRIC_PLANNERS_SPARSE_ROADMAP_SPANNER_
#include "ompl/geometric/planners/PlannerIncludes.h"
#include "ompl/datastructures/NearestNeighbors.h"
#include "ompl/geometric/PathSimplifier.h"
#include "ompl/util/Time.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 <deque>
#include <map>
#include <set>
namespace ompl
{
namespace geometric
{
class SPARS : public base::Planner
{
public:
enum GuardType
{
START,
GOAL,
COVERAGE,
CONNECTIVITY,
INTERFACE,
QUALITY,
};
struct vertex_state_t
{
using kind = boost::vertex_property_tag;
};
struct vertex_representative_t
{
using kind = boost::vertex_property_tag;
};
struct vertex_color_t
{
using kind = boost::vertex_property_tag;
};
struct vertex_list_t
{
using kind = boost::vertex_property_tag;
};
struct vertex_interface_list_t
{
using kind = boost::vertex_property_tag;
};
using VertexIndexType = unsigned long;
using InterfaceHash = std::unordered_map<VertexIndexType, std::set<VertexIndexType>>;
using DensePath = std::deque<base::State *>;
using SpannerGraph = 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_list_t, std::set<VertexIndexType>,
boost::property<vertex_interface_list_t,
InterfaceHash>>>>>>,
boost::property<boost::edge_weight_t, base::Cost>>;
using SparseVertex = boost::graph_traits<SpannerGraph>::vertex_descriptor;
using SparseEdge = boost::graph_traits<SpannerGraph>::edge_descriptor;
using SparseNeighbors = std::shared_ptr<NearestNeighbors<SparseVertex> >;
using DenseGraph = 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_representative_t, SparseVertex>>>>,
boost::property<boost::edge_weight_t, double>>;
using DenseVertex = boost::graph_traits<DenseGraph>::vertex_descriptor;
using DenseEdge = boost::graph_traits<DenseGraph>::edge_descriptor;
using DenseNeighbors = std::shared_ptr<NearestNeighbors<DenseVertex> >;
SPARS(const base::SpaceInformationPtr &si);
~SPARS() override;
void setProblemDefinition(const base::ProblemDefinitionPtr &pdef) override;
void getPlannerData(base::PlannerData &data) const override;
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 setDenseNeighbors()
{
nn_ = std::make_shared<NN<DenseVertex>>();
connectionStrategy_ = std::function<const std::vector<DenseVertex> &(const DenseVertex)>();
if (isSetup())
setup();
}
template <template <typename T> class NN>
void setSparseNeighbors()
{
snn_ = std::make_shared<NN<SparseVertex>>();
if (isSetup())
setup();
}
void setMaxFailures(unsigned int m)
{
maxFailures_ = m;
}
void setDenseDeltaFraction(double d)
{
denseDeltaFraction_ = d;
if (denseDelta_ > 0.0) // setup was previously called
denseDelta_ = d * si_->getMaximumExtent();
}
void setSparseDeltaFraction(double d)
{
sparseDeltaFraction_ = d;
if (sparseDelta_ > 0.0) // setup was previously called
sparseDelta_ = d * si_->getMaximumExtent();
}
void setStretchFactor(double t)
{
stretchFactor_ = t;
}
unsigned getMaxFailures() const
{
return maxFailures_;
}
double getDenseDeltaFraction() const
{
return denseDeltaFraction_;
}
double getSparseDeltaFraction() const
{
return sparseDeltaFraction_;
}
double getStretchFactor() const
{
return stretchFactor_;
}
void setup() override;
const DenseGraph &getDenseGraph() const
{
return g_;
}
const SpannerGraph &getRoadmap() const
{
return s_;
}
unsigned int milestoneCount() const
{
return boost::num_vertices(g_);
}
unsigned int guardCount() const
{
return boost::num_vertices(s_);
}
double averageValence() const;
void printDebug(std::ostream &out = std::cout) const;
bool reachedFailureLimit() 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:
DenseVertex addSample(base::State *workState, const base::PlannerTerminationCondition &ptc);
void checkQueryStateInitialization();
bool sameComponent(SparseVertex m1, SparseVertex m2);
DenseVertex addMilestone(base::State *state);
SparseVertex addGuard(base::State *state, GuardType type);
void connectSparsePoints(SparseVertex v, SparseVertex vp);
void connectDensePoints(DenseVertex v, DenseVertex vp);
bool checkAddCoverage(const base::State *lastState, const std::vector<SparseVertex> &neigh);
bool checkAddConnectivity(const base::State *lastState, const std::vector<SparseVertex> &neigh);
bool checkAddInterface(const std::vector<DenseVertex> &graphNeighborhood,
const std::vector<DenseVertex> &visibleNeighborhood, DenseVertex q);
bool checkAddPath(DenseVertex q, const std::vector<DenseVertex> &neigh);
DenseVertex getInterfaceNeighbor(DenseVertex q, SparseVertex rep);
bool addPathToSpanner(const DensePath &dense_path, SparseVertex vp, SparseVertex vpp);
void updateRepresentatives(SparseVertex v);
void calculateRepresentative(DenseVertex q);
void addToRepresentatives(DenseVertex q, SparseVertex rep, const std::set<SparseVertex> &oreps);
void removeFromRepresentatives(DenseVertex q, SparseVertex rep);
void computeVPP(DenseVertex v, DenseVertex vp, std::vector<SparseVertex> &VPPs);
void computeX(DenseVertex v, DenseVertex vp, DenseVertex vpp, std::vector<SparseVertex> &Xs);
void resetFailures();
void checkForSolution(const base::PlannerTerminationCondition &ptc, base::PathPtr &solution);
bool haveSolution(const std::vector<DenseVertex> &starts, const std::vector<DenseVertex> &goals,
base::PathPtr &solution);
bool reachedTerminationCriterion() const;
base::PathPtr constructSolution(SparseVertex start, SparseVertex goal) const;
void computeDensePath(DenseVertex start, DenseVertex goal, DensePath &path) const;
void freeMemory();
void getSparseNeighbors(base::State *inState, std::vector<SparseVertex> &graphNeighborhood);
void filterVisibleNeighbors(base::State *inState, const std::vector<SparseVertex> &graphNeighborhood,
std::vector<SparseVertex> &visibleNeighborhood) const;
void getInterfaceNeighborRepresentatives(DenseVertex q, std::set<SparseVertex> &interfaceRepresentatives);
void getInterfaceNeighborhood(DenseVertex q, std::vector<DenseVertex> &interfaceNeighborhood);
double distanceFunction(const DenseVertex a, const DenseVertex b) const
{
return si_->distance(stateProperty_[a], stateProperty_[b]);
}
double sparseDistanceFunction(const SparseVertex a, const SparseVertex b) const
{
return si_->distance(sparseStateProperty_[a], sparseStateProperty_[b]);
}
base::ValidStateSamplerPtr sampler_;
DenseNeighbors nn_;
SparseNeighbors snn_;
DenseGraph g_;
SpannerGraph s_;
std::vector<SparseVertex> startM_;
std::vector<SparseVertex> goalM_;
DenseVertex sparseQueryVertex_;
DenseVertex queryVertex_;
PathGeometric geomPath_;
boost::property_map<DenseGraph, vertex_state_t>::type stateProperty_;
boost::property_map<SpannerGraph, vertex_state_t>::type sparseStateProperty_;
boost::property_map<SpannerGraph, vertex_color_t>::type sparseColorProperty_;
boost::property_map<DenseGraph, vertex_representative_t>::type representativesProperty_;
boost::property_map<SpannerGraph, vertex_list_t>::type nonInterfaceListsProperty_;
boost::property_map<SpannerGraph, vertex_interface_list_t>::type interfaceListsProperty_;
PathSimplifierPtr psimp_;
boost::property_map<DenseGraph, boost::edge_weight_t>::type weightProperty_;
boost::disjoint_sets<boost::property_map<SpannerGraph, boost::vertex_rank_t>::type,
boost::property_map<SpannerGraph, boost::vertex_predecessor_t>::type> sparseDJSets_;
std::function<const std::vector<DenseVertex> &(const DenseVertex)> connectionStrategy_;
unsigned int consecutiveFailures_{0u};
double stretchFactor_{3.};
unsigned int maxFailures_{1000u};
bool addedSolution_{false};
double denseDeltaFraction_{.001};
double sparseDeltaFraction_{.25};
double denseDelta_{0.};
double sparseDelta_{0.};
RNG rng_;
mutable std::mutex graphMutex_;
base::OptimizationObjectivePtr opt_;
base::Cost costHeuristic(SparseVertex u, SparseVertex v) const;
// Planner progress properties
long unsigned int iterations_{0ul};
base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
};
}
}
#endif