Program Listing for File TSRRT.h

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

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2020, 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: Ryan Luna */

#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_TSRRT_
#define OMPL_GEOMETRIC_PLANNERS_RRT_TSRRT_

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

namespace ompl
{
    namespace geometric
    {
        OMPL_CLASS_FORWARD(TaskSpaceConfig);

        class TaskSpaceConfig
        {
        public:
            virtual ~TaskSpaceConfig()
            {
            }
            // Returns the dimension of the task space.
            virtual int getDimension() const = 0;
            // Project the c-space state into the task-space.
            virtual void project(const base::State *state, Eigen::Ref<Eigen::VectorXd> ts_proj) const = 0;

            // Sample point uniformly in task-space.
            virtual void sample(Eigen::Ref<Eigen::VectorXd> ts_proj) const = 0;

            // Given a point in task-space, generate a configuraton space state
            // that projects to this point.  seed is the nearest task-space neighbor.
            virtual bool lift(const Eigen::Ref<Eigen::VectorXd> &ts_proj, const base::State *seed,
                              base::State *state) const = 0;
        };

        class TSRRT : public base::Planner
        {
        public:
            TSRRT(const base::SpaceInformationPtr &si, const TaskSpaceConfigPtr &task_space);

            virtual ~TSRRT();

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

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

            virtual void clear();

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

            double getGoalBias() const
            {
                return goalBias_;
            }

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

            double getRange() const
            {
                return maxDistance_;
            }

            template <template <typename T> class NN>
            void setNearestNeighbors()
            {
                nn_.reset(new NN<Motion *>());
            }

            virtual void setup();

        protected:
            class Motion
            {
            public:
                Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(nullptr)
                {
                }

                ~Motion() = default;

                base::State *state{nullptr};

                Motion *parent{nullptr};

                // Projection of the state into the task space.
                Eigen::VectorXd proj;
            };

            void freeMemory();

            double distanceFunction(const Motion *a, const Motion *b) const
            {
                double sqr_dist = 0.0;
                for (int ix = 0; ix < a->proj.size(); ++ix)
                {
                    double sqr_val = (*b).proj[ix] - (*a).proj[ix];
                    sqr_val *= sqr_val;

                    sqr_dist += sqr_val;
                }
                return sqr_dist;
            }

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

            double goalBias_{0.05};

            double maxDistance_{0.};

            RNG rng_;

            Motion *lastGoalMotion_{nullptr};

            // Mapping to/from task space.
            TaskSpaceConfigPtr task_space_;
        };

    }  // namespace geometric
}  // namespace ompl

#endif