Program Listing for File FMT.h

Return to documentation for file (src/ompl/geometric/planners/fmt/FMT.h)

/*********************************************************************
* Software License Agreement (BSD License)
*
*  Copyright (c) 2013, Autonomous Systems Laboratory, Stanford University
*  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 Stanford 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.
*********************************************************************/

/* Authors: Ashley Clark (Stanford) and Wolfgang Pointner (AIT) */
/* Co-developers: Brice Rebsamen (Stanford), Tim Wheeler (Stanford)
                  Edward Schmerling (Stanford), and Javier V. Gómez (UC3M - Stanford)*/
/* Algorithm design: Lucas Janson (Stanford) and Marco Pavone (Stanford) */
/* Acknowledgements for insightful comments: Oren Salzman (Tel Aviv University),
 *                                           Joseph Starek (Stanford) */

#ifndef OMPL_GEOMETRIC_PLANNERS_FMT_
#define OMPL_GEOMETRIC_PLANNERS_FMT_

#include <ompl/geometric/planners/PlannerIncludes.h>
#include <ompl/base/goals/GoalSampleableRegion.h>
#include <ompl/datastructures/NearestNeighbors.h>
#include <ompl/datastructures/BinaryHeap.h>
#include <ompl/base/OptimizationObjective.h>
#include <map>

namespace ompl
{
    namespace geometric
    {
        class FMT : public ompl::base::Planner
        {
        public:
            FMT(const base::SpaceInformationPtr &si);

            ~FMT() override;

            void setup() override;

            base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;

            void clear() override;

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

            void setNumSamples(const unsigned int numSamples)
            {
                numSamples_ = numSamples;
            }

            unsigned int getNumSamples() const
            {
                return numSamples_;
            }

            void setNearestK(bool nearestK)
            {
                nearestK_ = nearestK;
            }

            bool getNearestK() const
            {
                return nearestK_;
            }

            void setRadiusMultiplier(const double radiusMultiplier)
            {
                if (radiusMultiplier <= 0.0)
                    throw Exception("Radius multiplier must be greater than zero");
                radiusMultiplier_ = radiusMultiplier;
            }

            double getRadiusMultiplier() const
            {
                return radiusMultiplier_;
            }

            void setFreeSpaceVolume(const double freeSpaceVolume)
            {
                if (freeSpaceVolume < 0.0)
                    throw Exception("Free space volume should be greater than zero");
                freeSpaceVolume_ = freeSpaceVolume;
            }

            double getFreeSpaceVolume() const
            {
                return freeSpaceVolume_;
            }

            void setCacheCC(bool ccc)
            {
                cacheCC_ = ccc;
            }

            bool getCacheCC() const
            {
                return cacheCC_;
            }

            void setHeuristics(bool h)
            {
                heuristics_ = h;
            }

            bool getHeuristics() const
            {
                return heuristics_;
            }

            void setExtendedFMT(bool e)
            {
                extendedFMT_ = e;
            }

            bool getExtendedFMT() const
            {
                return extendedFMT_;
            }

        protected:
            class Motion
            {
            public:
                enum SetType
                {
                    SET_CLOSED,
                    SET_OPEN,
                    SET_UNVISITED
                };

                Motion() = default;

                Motion(const base::SpaceInformationPtr &si)
                  : state_(si->allocState())
                {
                }

                ~Motion() = default;

                void setState(base::State *state)
                {
                    state_ = state;
                }

                base::State *getState() const
                {
                    return state_;
                }

                void setParent(Motion *parent)
                {
                    parent_ = parent;
                }

                Motion *getParent() const
                {
                    return parent_;
                }

                void setCost(const base::Cost cost)
                {
                    cost_ = cost;
                }

                base::Cost getCost() const
                {
                    return cost_;
                }

                void setSetType(const SetType currentSet)
                {
                    currentSet_ = currentSet;
                }

                SetType getSetType() const
                {
                    return currentSet_;
                }

                bool alreadyCC(Motion *m)
                {
                    return !(collChecksDone_.find(m) == collChecksDone_.end());
                }

                void addCC(Motion *m)
                {
                    collChecksDone_.insert(m);
                }

                void setHeuristicCost(const base::Cost h)
                {
                    hcost_ = h;
                }

                base::Cost getHeuristicCost() const
                {
                    return hcost_;
                }

                std::vector<Motion *> &getChildren()
                {
                    return children_;
                }

            protected:
                base::State *state_{nullptr};

                Motion *parent_{nullptr};

                base::Cost cost_{0.};

                base::Cost hcost_{0.};

                SetType currentSet_{SET_UNVISITED};

                std::set<Motion *> collChecksDone_;

                std::vector<Motion *> children_;
            };

            struct MotionCompare
            {
                MotionCompare() = default;

                /* Returns true if m1 is lower cost than m2. m1 and m2 must
                   have been instantiated with the same optimization objective */
                bool operator()(const Motion *m1, const Motion *m2) const
                {
                    if (heuristics_)
                        return opt_->isCostBetterThan(opt_->combineCosts(m1->getCost(), m1->getHeuristicCost()),
                                                      opt_->combineCosts(m2->getCost(), m2->getHeuristicCost()));
                    return opt_->isCostBetterThan(m1->getCost(), m2->getCost());
                }

                base::OptimizationObjective *opt_{nullptr};
                bool heuristics_{false};
            };

            double distanceFunction(const Motion *a, const Motion *b) const
            {
                return opt_->motionCost(a->getState(), b->getState()).value();
            }

            void freeMemory();

            void sampleFree(const ompl::base::PlannerTerminationCondition &ptc);

            void assureGoalIsSampled(const ompl::base::GoalSampleableRegion *goal);

            double calculateUnitBallVolume(unsigned int dimension) const;

            double calculateRadius(unsigned int dimension, unsigned int n) const;

            void saveNeighborhood(Motion *m);

            void traceSolutionPathThroughTree(Motion *goalMotion);

            bool expandTreeFromNode(Motion **z);

            void updateNeighborhood(Motion *m, std::vector<Motion *> nbh);

            Motion *getBestParent(Motion *m, std::vector<Motion *> &neighbors, base::Cost &cMin);

            using MotionBinHeap = ompl::BinaryHeap<Motion *, MotionCompare>;

            MotionBinHeap Open_;

            std::map<Motion *, std::vector<Motion *>> neighborhoods_;

            unsigned int numSamples_{1000u};

            unsigned int collisionChecks_{0u};

            bool nearestK_{true};

            bool cacheCC_{true};

            bool heuristics_{false};

            double NNr_;

            unsigned int NNk_;

            double freeSpaceVolume_;

            double radiusMultiplier_{1.1};

            std::shared_ptr<NearestNeighbors<Motion *>> nn_;

            base::StateSamplerPtr sampler_;

            base::OptimizationObjectivePtr opt_;

            Motion *lastGoalMotion_;

            base::State *goalState_;

            bool extendedFMT_{true};

            // For sorting a list of costs and getting only their sorted indices
            struct CostIndexCompare
            {
                CostIndexCompare(const std::vector<base::Cost> &costs, const base::OptimizationObjective &opt)
                  : costs_(costs), opt_(opt)
                {
                }
                bool operator()(unsigned i, unsigned j)
                {
                    return opt_.isCostBetterThan(costs_[i], costs_[j]);
                }
                const std::vector<base::Cost> &costs_;
                const base::OptimizationObjective &opt_;
            };
        };
    }
}

#endif  // OMPL_GEOMETRIC_PLANNERS_FMT_