Program Listing for File SimpleSetup.h

Return to documentation for file (src/ompl/geometric/SimpleSetup.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_GEOMETRIC_SIMPLE_SETUP_
#define OMPL_GEOMETRIC_SIMPLE_SETUP_

#include "ompl/base/Planner.h"
#include "ompl/base/PlannerData.h"
#include "ompl/base/SpaceInformation.h"
#include "ompl/base/ProblemDefinition.h"
#include "ompl/geometric/PathGeometric.h"
#include "ompl/geometric/PathSimplifier.h"
#include "ompl/util/Console.h"
#include "ompl/util/Exception.h"

namespace ompl
{
    namespace geometric
    {
        OMPL_CLASS_FORWARD(SimpleSetup);

        class SimpleSetup
        {
        public:
            explicit SimpleSetup(const base::SpaceInformationPtr &si);

            explicit SimpleSetup(const base::StateSpacePtr &space);

            virtual ~SimpleSetup() = default;

            const base::SpaceInformationPtr &getSpaceInformation() const
            {
                return si_;
            }

            const base::ProblemDefinitionPtr &getProblemDefinition() const
            {
                return pdef_;
            }

            base::ProblemDefinitionPtr &getProblemDefinition()
            {
                return pdef_;
            }

            const base::StateSpacePtr &getStateSpace() const
            {
                return si_->getStateSpace();
            }

            const base::StateValidityCheckerPtr &getStateValidityChecker() const
            {
                return si_->getStateValidityChecker();
            }

            const base::GoalPtr &getGoal() const
            {
                return pdef_->getGoal();
            }

            const base::PlannerPtr &getPlanner() const
            {
                return planner_;
            }

            const base::PlannerAllocator &getPlannerAllocator() const
            {
                return pa_;
            }

            const PathSimplifierPtr &getPathSimplifier() const
            {
                return psk_;
            }

            PathSimplifierPtr &getPathSimplifier()
            {
                return psk_;
            }

            const base::OptimizationObjectivePtr &getOptimizationObjective() const
            {
                return pdef_->getOptimizationObjective();
            }

            bool haveExactSolutionPath() const
            {
                return pdef_->hasExactSolution();
            }

            bool haveSolutionPath() const
            {
                return pdef_->hasSolution();
            }

            const std::string getSolutionPlannerName() const;

            PathGeometric &getSolutionPath() const;

            void getPlannerData(base::PlannerData &pd) const;

            void setStateValidityChecker(const base::StateValidityCheckerPtr &svc)
            {
                si_->setStateValidityChecker(svc);
            }

            void setStateValidityChecker(const base::StateValidityCheckerFn &svc)
            {
                si_->setStateValidityChecker(svc);
            }

            void setOptimizationObjective(const base::OptimizationObjectivePtr &optimizationObjective)
            {
                pdef_->setOptimizationObjective(optimizationObjective);
            }

            void setStartAndGoalStates(const base::ScopedState<> &start, const base::ScopedState<> &goal,
                                       double threshold = std::numeric_limits<double>::epsilon());

            void addStartState(const base::ScopedState<> &state)
            {
                pdef_->addStartState(state);
            }

            void clearStartStates()
            {
                pdef_->clearStartStates();
            }

            void setStartState(const base::ScopedState<> &state)
            {
                clearStartStates();
                addStartState(state);
            }

            void setGoalState(const base::ScopedState<> &goal,
                              double threshold = std::numeric_limits<double>::epsilon());

            void setGoal(const base::GoalPtr &goal);

            void setPlanner(const base::PlannerPtr &planner)
            {
                if (planner && planner->getSpaceInformation().get() != si_.get())
                    throw Exception("Planner instance does not match space information");
                planner_ = planner;
                configured_ = false;
            }

            void setPlannerAllocator(const base::PlannerAllocator &pa)
            {
                pa_ = pa;
                planner_.reset();
                configured_ = false;
            }

            virtual base::PlannerStatus solve(double time = 1.0);

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

            base::PlannerStatus getLastPlannerStatus() const
            {
                return lastStatus_;
            }

            double getLastPlanComputationTime() const
            {
                return planTime_;
            }

            double getLastSimplificationTime() const
            {
                return simplifyTime_;
            }

            void simplifySolution(double duration = 0.0);

            void simplifySolution(const base::PlannerTerminationCondition &ptc);

            virtual void clear();

            virtual void print(std::ostream &out = std::cout) const;

            virtual void setup();

        protected:
            base::SpaceInformationPtr si_;

            base::ProblemDefinitionPtr pdef_;

            base::PlannerPtr planner_;

            base::PlannerAllocator pa_;

            PathSimplifierPtr psk_;

            bool configured_;

            double planTime_;

            double simplifyTime_;

            base::PlannerStatus lastStatus_;
        };
    }  // namespace geometric
}  // namespace ompl
#endif