Program Listing for File STRRTstar.h

Return to documentation for file (src/ompl/geometric/planners/rrt/STRRTstar.h)

/*********************************************************************
* Software License Agreement (BSD License)
*
*  Copyright (c) 2021, Technische Universität Berlin (TU Berlin)
*  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 the TU Berlin 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: Francesco Grothe */

#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_STRRT_STAR_
#define OMPL_GEOMETRIC_PLANNERS_RRT_STRRT_STAR_

#include <ompl/datastructures/NearestNeighbors.h>
#include <ompl/base/goals/GoalSampleableRegion.h>
#include <ompl/geometric/planners/PlannerIncludes.h>
#include <ompl/base/OptimizationObjective.h>
#include <ompl/base/spaces/SpaceTimeStateSpace.h>
#include <ompl/base/objectives/MinimizeArrivalTime.h>
#include <ompl/base/samplers/ConditionalStateSampler.h>
#include <ompl/tools/config/SelfConfig.h>
#include <ompl/util/GeometricEquations.h>
#include <boost/math/constants/constants.hpp>

namespace ompl
{
    namespace geometric
    {
        class STRRTstar : public base::Planner
        {
        public:
            using Motion = base::ConditionalStateSampler::Motion;

            explicit STRRTstar(const ompl::base::SpaceInformationPtr &si);

            ~STRRTstar() override;

            void clear() override;

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

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

            void setRange(double distance);

            double getRange() const;

            double getOptimumApproxFactor() const;

            void setOptimumApproxFactor(double optimumApproxFactor);

            std::string getRewiringState() const;

            void setRewiringToOff();

            void setRewiringToRadius();

            void setRewiringToKNearest();

            double getRewireFactor() const;

            void setRewireFactor(double v);

            unsigned int getBatchSize() const;

            void setBatchSize(int v);

            void setTimeBoundFactorIncrease(double f);

            void setInitialTimeBoundFactor(double f);

            void setSampleUniformForUnboundedTime(bool uniform);

            void setup() override;

            using TreeData = std::shared_ptr<ompl::NearestNeighbors<Motion *>>;
        protected:

            struct TreeGrowingInfo
            {
                base::State *xstate;
                Motion *xmotion;
                bool start;
            };

            enum GrowState
            {
                TRAPPED,
                ADVANCED,
                REACHED
            };

            GrowState growTreeSingle(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion, Motion *nmotion);

            GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion, std::vector<Motion *> &nbh,
                               bool connect);

            void increaseTimeBound(bool hasEqualBounds, double &oldBatchTimeBoundFactor, double &newBatchTimeBoundFactor,
                                   bool &startTree, unsigned int &batchSize, int &numBatchSamples);

            void getNeighbors(TreeData &tree, Motion *motion, std::vector<Motion *> &nbh) const;

            void freeMemory();

            double distanceFunction(const Motion *a, const Motion *b) const
            {
                return si_->distance(a->state, b->state);
            }

            void pruneStartTree();

            Motion *pruneGoalTree();

            static Motion *computeSolutionMotion(Motion *motion);

            void removeInvalidGoals(const std::vector<Motion *> &invalidGoals);

            base::ConditionalStateSampler sampler_;

            TreeData tStart_;

            TreeData tGoal_;

            double maxDistance_{0.};

            double distanceBetweenTrees_;

            base::PathPtr bestSolution_{nullptr};

            double bestTime_ = std::numeric_limits<double>::infinity();

            unsigned int numIterations_ = 0;

            int numSolutions_ = 0;

            double minimumTime_ = std::numeric_limits<double>::infinity();

            double upperTimeBound_;

            double optimumApproxFactor_ = 1.0;

            Motion *startMotion_{nullptr};

            std::vector<Motion *> goalMotions_{};

            std::vector<Motion *> newBatchGoalMotions_{};

            base::State *tempState_{nullptr};  // temporary sampled goal states are stored here.

            base::State *nextGoal(int n, double oldBatchTimeBoundFactor, double newBatchTimeBoundFactor);

            base::State *nextGoal(const base::PlannerTerminationCondition &ptc, double oldBatchTimeBoundFactor,
                                  double newBatchTimeBoundFactor);

            base::State *nextGoal(const base::PlannerTerminationCondition &ptc, int n, double oldBatchTimeBoundFactor,
                                  double newBatchTimeBoundFactor);

            bool sampleGoalTime(base::State *goal, double oldBatchTimeBoundFactor, double newBatchTimeBoundFactor);

            static void removeFromParent(Motion *m);

            static void addDescendants(Motion *m, const TreeData &tree);

            void constructSolution(Motion *startMotion, Motion *goalMotion,
                                   const base::ReportIntermediateSolutionFn &intermediateSolutionCallback,
                                   const ompl::base::PlannerTerminationCondition& ptc);

            enum RewireState
            {
                // use r-disc search for rewiring
                RADIUS,
                // use k-nearest for rewiring
                KNEAREST,
                // don't use any rewiring
                OFF
            };

            RewireState rewireState_ = KNEAREST;

            double rewireFactor_{1.1};

            double k_rrt_{0u};

            double r_rrt_{0.};

            void calculateRewiringLowerBounds();

            bool rewireGoalTree(Motion *addedMotion);

            bool isTimeBounded_;

            double initialTimeBound_;

            unsigned int initialBatchSize_ = 512;

            double initialTimeBoundFactor_ = 2.0;

            double timeBoundFactorIncrease_ = 2.0;

            bool sampleOldBatch_ = true;

            bool sampleUniformForUnboundedTime_ = true;

            int goalStateSampleRatio_ = 4;

            ompl::RNG rng_;
        };
    }  // namespace geometric
}  // namespace ompl

#endif