Program Listing for File Planner.h

Return to documentation for file (src/ompl/base/Planner.h)

/*********************************************************************
* Software License Agreement (BSD License)
*
*  Copyright (c) 2010, 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 the 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: Ioan Sucan */

#ifndef OMPL_BASE_PLANNER_
#define OMPL_BASE_PLANNER_

#include "ompl/base/SpaceInformation.h"
#include "ompl/base/ProblemDefinition.h"
#include "ompl/base/PlannerData.h"
#include "ompl/base/PlannerStatus.h"
#include "ompl/base/PlannerTerminationCondition.h"
#include "ompl/base/GenericParam.h"
#include "ompl/util/Console.h"
#include "ompl/util/Time.h"
#include "ompl/util/ClassForward.h"
#include <functional>
#include <boost/concept_check.hpp>
#include <string>
#include <map>

namespace ompl
{
    namespace base
    {

        OMPL_CLASS_FORWARD(Planner);

        class PlannerInputStates
        {
        public:
            PlannerInputStates(const PlannerPtr &planner) : planner_(planner.get())
            {
                tempState_ = nullptr;
                update();
            }

            PlannerInputStates(const Planner *planner) : planner_(planner)
            {
                tempState_ = nullptr;
                update();
            }

            PlannerInputStates()
            {
                tempState_ = nullptr;
                clear();
            }

            ~PlannerInputStates()
            {
                clear();
            }

            void clear();

            void restart();

            bool update();

            bool use(const ProblemDefinitionPtr &pdef);

            void checkValidity() const;

            const State *nextStart();

            const State *nextGoal(const PlannerTerminationCondition &ptc);

            const State *nextGoal();

            bool haveMoreStartStates() const;

            bool haveMoreGoalStates() const;

            unsigned int getSeenStartStatesCount() const
            {
                return addedStartStates_;
            }

            unsigned int getSampledGoalsCount() const
            {
                return sampledGoalsCount_;
            }

        private:
            const Planner *planner_{nullptr};

            unsigned int addedStartStates_;
            unsigned int sampledGoalsCount_;
            State *tempState_;

            ProblemDefinitionPtr pdef_;
            const SpaceInformation *si_;
        };

        struct PlannerSpecs
        {
            PlannerSpecs() = default;

            GoalType recognizedGoal{GOAL_ANY};

            bool multithreaded{false};

            bool approximateSolutions{false};

            bool optimizingPaths{false};

            bool directed{false};

            bool provingSolutionNonExistence{false};

            bool canReportIntermediateSolutions{false};
        };

        class Planner
        {
        public:
            // non-copyable
            Planner(const Planner &) = delete;
            Planner &operator=(const Planner &) = delete;

            Planner(SpaceInformationPtr si, std::string name);

            virtual ~Planner() = default;

            template <class T>
            T *as()
            {
                BOOST_CONCEPT_ASSERT((boost::Convertible<T *, Planner *>));

                return static_cast<T *>(this);
            }

            template <class T>
            const T *as() const
            {
                BOOST_CONCEPT_ASSERT((boost::Convertible<T *, Planner *>));

                return static_cast<const T *>(this);
            }

            const SpaceInformationPtr &getSpaceInformation() const;

            const ProblemDefinitionPtr &getProblemDefinition() const;

            ProblemDefinitionPtr &getProblemDefinition();

            const PlannerInputStates &getPlannerInputStates() const;

            virtual void setProblemDefinition(const ProblemDefinitionPtr &pdef);

            virtual PlannerStatus solve(const PlannerTerminationCondition &ptc) = 0;

            PlannerStatus solve(const PlannerTerminationConditionFn &ptc, double checkInterval);

            PlannerStatus solve(double solveTime);

            virtual void clear();

            virtual void clearQuery();

            virtual void getPlannerData(PlannerData &data) const;

            const std::string &getName() const;

            void setName(const std::string &name);

            const PlannerSpecs &getSpecs() const;

            virtual void setup();

            virtual void checkValidity();

            bool isSetup() const;

            ParamSet &params()
            {
                return params_;
            }

            const ParamSet &params() const
            {
                return params_;
            }

            using PlannerProgressProperty = std::function<std::string()>;

            using PlannerProgressProperties = std::map<std::string, PlannerProgressProperty>;

            const PlannerProgressProperties &getPlannerProgressProperties() const
            {
                return plannerProgressProperties_;
            }

            virtual void printProperties(std::ostream &out) const;

            virtual void printSettings(std::ostream &out) const;

        protected:
            template <typename T, typename PlannerType, typename SetterType, typename GetterType>
            void declareParam(const std::string &name, const PlannerType &planner, const SetterType &setter,
                              const GetterType &getter, const std::string &rangeSuggestion = "")
            {
                params_.declareParam<T>(name,
                                        [planner, setter](T param)
                                        {
                                            (*planner.*setter)(param);
                                        },
                                        [planner, getter]
                                        {
                                            return (*planner.*getter)();
                                        });
                if (!rangeSuggestion.empty())
                    params_[name].setRangeSuggestion(rangeSuggestion);
            }

            template <typename T, typename PlannerType, typename SetterType>
            void declareParam(const std::string &name, const PlannerType &planner, const SetterType &setter,
                              const std::string &rangeSuggestion = "")
            {
                params_.declareParam<T>(name, [planner, setter](T param)
                                        {
                                            (*planner.*setter)(param);
                                        });
                if (!rangeSuggestion.empty())
                    params_[name].setRangeSuggestion(rangeSuggestion);
            }

            void addPlannerProgressProperty(const std::string &progressPropertyName,
                                            const PlannerProgressProperty &prop)
            {
                plannerProgressProperties_[progressPropertyName] = prop;
            }

            SpaceInformationPtr si_;

            ProblemDefinitionPtr pdef_;

            PlannerInputStates pis_;

            std::string name_;

            PlannerSpecs specs_;

            ParamSet params_;

            PlannerProgressProperties plannerProgressProperties_;

            bool setup_;
        };

        using PlannerAllocator = std::function<PlannerPtr(const SpaceInformationPtr &)>;
    }
}

#endif