Program Listing for File STRIDE.h

Return to documentation for file (src/ompl/geometric/planners/stride/STRIDE.h)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2013, Rice 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 Rice 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: Bryant Gipson, Mark Moll */

#ifndef OMPL_GEOMETRIC_PLANNERS_STRIDE_STRIDE_
#define OMPL_GEOMETRIC_PLANNERS_STRIDE_STRIDE_

#include "ompl/datastructures/Grid.h"
#include "ompl/geometric/planners/PlannerIncludes.h"
#include "ompl/base/ProjectionEvaluator.h"
#include "ompl/datastructures/PDF.h"
#include <unordered_map>
#include <boost/scoped_ptr.hpp>
#include <vector>

namespace ompl
{
    template <typename _T>
    class NearestNeighborsGNAT;

    namespace geometric
    {
        class STRIDE : public base::Planner
        {
        public:
            STRIDE(const base::SpaceInformationPtr &si, bool useProjectedDistance = false, unsigned int degree = 16,
                   unsigned int minDegree = 12, unsigned int maxDegree = 18, unsigned int maxNumPtsPerLeaf = 6,
                   double estimatedDimension = 0.0);
            ~STRIDE() override;

            void setup() override;

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

            void clear() override;

            void setGoalBias(double goalBias)
            {
                goalBias_ = goalBias;
            }

            double getGoalBias() const
            {
                return goalBias_;
            }

            void setUseProjectedDistance(bool useProjectedDistance)
            {
                useProjectedDistance_ = useProjectedDistance;
            }
            bool getUseProjectedDistance() const
            {
                return useProjectedDistance_;
            }

            void setDegree(unsigned int degree)
            {
                degree_ = degree;
            }
            unsigned int getDegree() const
            {
                return degree_;
            }
            void setMinDegree(unsigned int minDegree)
            {
                minDegree_ = minDegree;
            }
            unsigned int getMinDegree() const
            {
                return minDegree_;
            }
            void setMaxDegree(unsigned int maxDegree)
            {
                maxDegree_ = maxDegree;
            }
            unsigned int getMaxDegree() const
            {
                return maxDegree_;
            }
            void setMaxNumPtsPerLeaf(unsigned int maxNumPtsPerLeaf)
            {
                maxNumPtsPerLeaf_ = maxNumPtsPerLeaf;
            }
            unsigned int getMaxNumPtsPerLeaf() const
            {
                return maxNumPtsPerLeaf_;
            }
            void setEstimatedDimension(double estimatedDimension)
            {
                estimatedDimension_ = estimatedDimension;
            }
            double getEstimatedDimension() const
            {
                return estimatedDimension_;
            }

            void setRange(double distance)
            {
                maxDistance_ = distance;
            }

            double getRange() const
            {
                return maxDistance_;
            }
            void setMinValidPathFraction(double fraction)
            {
                minValidPathFraction_ = fraction;
            }

            double getMinValidPathFraction() const
            {
                return minValidPathFraction_;
            }
            void setProjectionEvaluator(const base::ProjectionEvaluatorPtr &projectionEvaluator)
            {
                projectionEvaluator_ = projectionEvaluator;
            }

            void setProjectionEvaluator(const std::string &name)
            {
                projectionEvaluator_ = si_->getStateSpace()->getProjection(name);
            }

            const base::ProjectionEvaluatorPtr &getProjectionEvaluator() const
            {
                return projectionEvaluator_;
            }

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

        protected:
            class Motion
            {
            public:
                Motion() = default;

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

                ~Motion() = default;

                base::State *state{nullptr};

                Motion *parent{nullptr};
            };

            void freeMemory();

            void setupTree();

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

            double projectedDistanceFunction(const Motion *a, const Motion *b) const
            {
                unsigned int num_dims = projectionEvaluator_->getDimension();
                Eigen::VectorXd aproj(num_dims), bproj(num_dims);
                projectionEvaluator_->project(a->state, aproj);
                projectionEvaluator_->project(b->state, bproj);
                return (aproj - bproj).norm();
            }

            void addMotion(Motion *motion);

            Motion *selectMotion();

            base::ValidStateSamplerPtr sampler_;

            base::ProjectionEvaluatorPtr projectionEvaluator_;

            boost::scoped_ptr<NearestNeighborsGNAT<Motion *>> tree_;

            double goalBias_{.05};

            double maxDistance_{0.};

            bool useProjectedDistance_;
            unsigned int degree_;
            unsigned int minDegree_;
            unsigned int maxDegree_;
            unsigned int maxNumPtsPerLeaf_;
            double estimatedDimension_;
            double minValidPathFraction_{.2};

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

#endif