Program Listing for File SPARSdb.h

Return to documentation for file (src/ompl/tools/thunder/SPARSdb.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, Dave Coleman */

#ifndef OMPL_TOOLS_THUNDER_SPARS_DB_
#define OMPL_TOOLS_THUNDER_SPARS_DB_

#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/graph/filtered_graph.hpp>
#include <boost/graph/graph_utility.hpp>
#include <boost/graph/astar_search.hpp>
#include <boost/graph/connected_components.hpp>
#include <boost/property_map/property_map.hpp>
#include <boost/pending/disjoint_sets.hpp>
#include <thread>
#include <iostream>
#include <fstream>
#include <utility>
#include <vector>
#include <map>

namespace ompl
{
    namespace geometric
    {
        class SPARSdb : public base::Planner
        {
        public:
            enum GuardType
            {
                START,
                GOAL,
                COVERAGE,
                CONNECTIVITY,
                INTERFACE,
                QUALITY,
            };

            // BOOST GRAPH DETAILS

            using VertexIndexType = unsigned long int;

            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>;

            // The InterfaceHash structure is wrapped inside of this struct due to a compilation error on
            // GCC 4.6 with Boost 1.48.  An implicit assignment operator overload does not compile with these
            // components, so an explicit overload is given here.
            // Remove this struct when the minimum Boost requirement is > v1.48.
            struct InterfaceHashStruct
            {
                InterfaceHash interfaceHash;
            };

            // Vertex properties

            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;
            };

            // Edge properties

            struct edge_collision_state_t
            {
                using kind = boost::edge_property_tag;
            };

            enum EdgeCollisionState
            {
                NOT_CHECKED,
                IN_COLLISION,
                FREE
            };

            struct CandidateSolution
            {
                bool isApproximate_;
                base::PathPtr path_;
                // Edge 0 is edge from vertex 0 to vertex 1. Thus, there is n-1 edges for n vertices
                std::vector<EdgeCollisionState> edgeCollisionStatus_;
                // TODO save the collision state of the vertexes also?

                std::size_t getStateCount()
                {
                    return static_cast<ompl::geometric::PathGeometric &>(*path_).getStateCount();
                }

                ompl::geometric::PathGeometric &getGeometricPath()
                {
                    return static_cast<ompl::geometric::PathGeometric &>(*path_);
                }
            };


            using VertexProperties = 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, InterfaceHashStruct>>>>>;

            using EdgeProperties =
                boost::property<boost::edge_weight_t, double, boost::property<edge_collision_state_t, int>>;

            using Graph = boost::adjacency_list<boost::vecS,  // store in std::vector
                                                boost::vecS,  // store in std::vector
                                                boost::undirectedS, VertexProperties, EdgeProperties>;

            using Vertex = boost::graph_traits<Graph>::vertex_descriptor;

            using Edge = boost::graph_traits<Graph>::edge_descriptor;

            // Typedefs for property maps

            using EdgeCollisionStateMap = boost::property_map<Graph, edge_collision_state_t>::type;


            class edgeWeightMap
            {
            private:
                const Graph &g_;  // Graph used
                const EdgeCollisionStateMap &collisionStates_;

            public:
                using key_type = Edge;
                using value_type = double;
                using reference = double &;
                using category = boost::readable_property_map_tag;

                edgeWeightMap(const Graph &graph, const EdgeCollisionStateMap &collisionStates);

                double get(Edge e) const;
            };


            class foundGoalException
            {
            };


            class CustomVisitor : public boost::default_astar_visitor
            {
            private:
                Vertex goal;  // Goal Vertex of the search

            public:
                CustomVisitor(Vertex goal);

                void examine_vertex(Vertex u, const Graph &g) const;
            };

            // SPARS MEMBER FUNCTIONS

            SPARSdb(const base::SpaceInformationPtr &si);

            ~SPARSdb() 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_;
            }

            bool getGuardSpacingFactor(double pathLength, double &numGuards, double &spacingFactor);

            bool getGuardSpacingFactor(double pathLength, int &numGuards, double &spacingFactor);

            bool addPathToRoadmap(const base::PlannerTerminationCondition &ptc,
                                  ompl::geometric::PathGeometric &solutionPath);

            bool checkStartGoalConnection(ompl::geometric::PathGeometric &solutionPath);

            bool addStateToRoadmap(const base::PlannerTerminationCondition &ptc, base::State *newState);

            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();
            }

            bool getSimilarPaths(int nearestK, const base::State *start, const base::State *goal,
                                 CandidateSolution &candidateSolution, const base::PlannerTerminationCondition &ptc);

            void setup() override;

            const Graph &getRoadmap() const
            {
                return g_;
            }

            unsigned int getNumVertices() const
            {
                return boost::num_vertices(g_);
            }

            unsigned int getNumEdges() const
            {
                return boost::num_edges(g_);
            }

            unsigned int getNumConnectedComponents() const
            {
                // Make sure graph is populated
                if (getNumVertices() == 0u)
                    return 0;

                std::vector<int> components(boost::num_vertices(g_));

                // it always overcounts by 1, i think because it is missing vertex 0 which is the new state insertion
                // component
                return boost::connected_components(g_, &components[0]) - 1;
            }

            unsigned int getNumPathInsertionFailed() const
            {
                return numPathInsertionFailures_;
            }

            unsigned int getNumConsecutiveFailures() const
            {
                return consecutiveFailures_;
            }

            long unsigned int getIterations() const
            {
                return iterations_;
            }

            bool convertVertexPathToStatePath(std::vector<Vertex> &vertexPath, const base::State *actualStart,
                                              const base::State *actualGoal, CandidateSolution &candidateSolution,
                                              bool disableCollisionWarning = false);

            void getPlannerData(base::PlannerData &data) const override;

            void setPlannerData(const base::PlannerData &data);

            bool reachedFailureLimit() const;

            void printDebug(std::ostream &out = std::cout) const;

            void clearEdgeCollisionStates();

        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 *state, std::vector<Vertex> &graphNeighborhood,
                                    std::vector<Vertex> &visibleNeighborhood);

            bool findGraphNeighbors(const base::State *state, std::vector<Vertex> &graphNeighborhood);

            void approachGraph(Vertex v);

            Vertex findGraphRepresentative(base::State *st);

            void findCloseRepresentatives(base::State *workState, 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 getPaths(const std::vector<Vertex> &candidateStarts, const std::vector<Vertex> &candidateGoals,
                          const base::State *actualStart, const base::State *actualGoal,
                          CandidateSolution &candidateSolution, const base::PlannerTerminationCondition &ptc);

            bool lazyCollisionSearch(const Vertex &start, const Vertex &goal, const base::State *actualStart,
                                     const base::State *actualGoal, CandidateSolution &candidateSolution,
                                     const base::PlannerTerminationCondition &ptc);

            bool lazyCollisionCheck(std::vector<Vertex> &vertexPath, const base::PlannerTerminationCondition &ptc);

            void checkForSolution(const base::PlannerTerminationCondition &ptc, base::PathPtr &solution);

            bool constructSolution(Vertex start, Vertex goal, std::vector<Vertex> &vertexPath) 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_{5000u};

            unsigned int numPathInsertionFailures_{0u};

            unsigned int nearSamplePoints_;

            PathSimplifierPtr psimp_;

            boost::property_map<Graph, boost::edge_weight_t>::type edgeWeightProperty_;  // TODO: this is not used

            EdgeCollisionStateMap edgeCollisionStateProperty_;

            boost::property_map<Graph, vertex_state_t>::type stateProperty_;

            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_{0u};

            long unsigned int iterations_{0ul};

            double sparseDelta_{0.};

            double denseDelta_{0.};

            std::vector<Vertex> startVertexCandidateNeighbors_;
            std::vector<Vertex> goalVertexCandidateNeighbors_;

            bool verbose_{false};
        };
    }
}

#endif