Program Listing for File TRRT.h

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

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2008, Willow Garage, Inc.
 *  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 Willow Garage 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: Dave Coleman, Ryan Luna */

#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_TRRT_
#define OMPL_GEOMETRIC_PLANNERS_RRT_TRRT_

#include "ompl/geometric/planners/PlannerIncludes.h"
#include "ompl/datastructures/NearestNeighbors.h"
#include "ompl/base/OptimizationObjective.h"

/*
  NOTES:
  **Variable Names that have been converted to longer versions from standards:
  nearest_neighbors_ -> nn_
  planner_termination_condition -> ptc

  **Inherited Member Variables Key:
  si_ -> SpaceInformation
  pdef_ -> ProblemDefinition
  pis_ -> PlannerInputStates - Utility class to extract valid input states
*/

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

            ~TRRT() override;

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

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

            void clear() override;

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

            double getGoalBias() const
            {
                return goalBias_;
            }

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

            double getRange() const
            {
                return maxDistance_;
            }

            void setTempChangeFactor(double factor)
            {
                tempChangeFactor_ = exp(factor);
            }

            double getTempChangeFactor() const
            {
                return log(tempChangeFactor_);
            }

            void setCostThreshold(double maxCost)
            {
                costThreshold_ = base::Cost(maxCost);
            }

            double getCostThreshold() const
            {
                return costThreshold_.value();
            }

            void setInitTemperature(double initTemperature)
            {
                initTemperature_ = initTemperature;
                temp_ = initTemperature_;
            }

            double getInitTemperature() const
            {
                return initTemperature_;
            }

            void setFrontierThreshold(double frontier_threshold)
            {
                frontierThreshold_ = frontier_threshold;
            }

            double getFrontierThreshold() const
            {
                return frontierThreshold_;
            }

            void setFrontierNodeRatio(double frontierNodeRatio)
            {
                frontierNodeRatio_ = frontierNodeRatio;
            }

            double getFrontierNodeRatio() const
            {
                return frontierNodeRatio_;
            }

            template <template <typename T> class NN>
            void setNearestNeighbors()
            {
                if (nearestNeighbors_->size() == 0)
                    OMPL_WARN("Calling setNearestNeighbors will clear all states.");
                clear();
                nearestNeighbors_ = std::make_shared<NN<Motion *>>();
                setup();
            }

            void setup() override;

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

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

                ~Motion() = default;

                base::State *state{nullptr};

                Motion *parent{nullptr};

                base::Cost cost;
            };

            void freeMemory();

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

            bool transitionTest(const base::Cost &motionCost);

            bool minExpansionControl(double randMotionDistance);

            base::StateSamplerPtr sampler_;

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

            double goalBias_{.05};

            double maxDistance_{0.};

            RNG rng_;

            Motion *lastGoalMotion_{nullptr};

            // *********************************************************************************************************
            // TRRT-Specific Variables
            // *********************************************************************************************************

            // Transtion Test -----------------------------------------------------------------------

            double temp_;

            base::Cost bestCost_;

            base::Cost worstCost_;

            base::Cost costThreshold_;

            double tempChangeFactor_;

            double initTemperature_;

            // Minimum Expansion Control --------------------------------------------------------------

            double nonfrontierCount_;
            double frontierCount_;

            double frontierThreshold_;

            double frontierNodeRatio_;

            ompl::base::OptimizationObjectivePtr opt_;
        };
    }
}

#endif