|
| 1 | +/********************************************************************* |
| 2 | + * Software License Agreement (BSD License) |
| 3 | + * |
| 4 | + * Copyright (c) 2008, Willow Garage, Inc. |
| 5 | + * All rights reserved. |
| 6 | + * |
| 7 | + * Redistribution and use in source and binary forms, with or without |
| 8 | + * modification, are permitted provided that the following conditions |
| 9 | + * are met: |
| 10 | + * |
| 11 | + * * Redistributions of source code must retain the above copyright |
| 12 | + * notice, this list of conditions and the following disclaimer. |
| 13 | + * * Redistributions in binary form must reproduce the above |
| 14 | + * copyright notice, this list of conditions and the following |
| 15 | + * disclaimer in the documentation and/or other materials provided |
| 16 | + * with the distribution. |
| 17 | + * * Neither the name of the Willow Garage nor the names of its |
| 18 | + * contributors may be used to endorse or promote products derived |
| 19 | + * from this software without specific prior written permission. |
| 20 | + * |
| 21 | + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 22 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
| 23 | + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
| 24 | + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
| 25 | + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
| 26 | + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
| 27 | + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
| 28 | + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 29 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
| 30 | + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
| 31 | + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 32 | + * POSSIBILITY OF SUCH DAMAGE. |
| 33 | + *********************************************************************/ |
| 34 | + |
| 35 | +/* Author: Ioan Sucan */ |
| 36 | + |
| 37 | +#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_AOX_RRT_CONNECT_ |
| 38 | +#define OMPL_GEOMETRIC_PLANNERS_RRT_AOX_RRT_CONNECT_ |
| 39 | + |
| 40 | +#include "ompl/datastructures/NearestNeighbors.h" |
| 41 | +#include "ompl/base/OptimizationObjective.h" |
| 42 | +#include "ompl/geometric/planners/PlannerIncludes.h" |
| 43 | + |
| 44 | +#include "ompl/base/Path.h" |
| 45 | + |
| 46 | +namespace ompl |
| 47 | +{ |
| 48 | + namespace geometric |
| 49 | + { |
| 50 | + /** |
| 51 | + @anchor gRRTC |
| 52 | + @par Short description |
| 53 | + The basic idea is to grow two RRTs, one from the start and |
| 54 | + one from the goal, and attempt to connect them. |
| 55 | + @par External documentation |
| 56 | + J. Kuffner and S.M. LaValle, RRT-connect: An efficient approach to single-query path planning, in <em>Proc. |
| 57 | + 2000 IEEE Intl. Conf. on Robotics and Automation</em>, pp. 995–1001, Apr. 2000. DOI: |
| 58 | + [10.1109/ROBOT.2000.844730](http://dx.doi.org/10.1109/ROBOT.2000.844730)<br> |
| 59 | + [[PDF]](http://ieeexplore.ieee.org/ielx5/6794/18246/00844730.pdf?tp=&arnumber=844730&isnumber=18246) |
| 60 | + [[more]](http://msl.cs.uiuc.edu/~lavalle/rrtpubs.html) |
| 61 | + */ |
| 62 | + |
| 63 | + /** \brief RRT-Connect (AOXRRTConnect) */ |
| 64 | + class AOXRRTConnect : public base::Planner |
| 65 | + { |
| 66 | + public: |
| 67 | + /** \brief Constructor */ |
| 68 | + AOXRRTConnect(const base::SpaceInformationPtr &si, bool addIntermediateStates = false); |
| 69 | + |
| 70 | + ~AOXRRTConnect() override; |
| 71 | + |
| 72 | + void getPlannerData(base::PlannerData &data) const override; |
| 73 | + |
| 74 | + base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override; |
| 75 | + |
| 76 | + void clear() override; |
| 77 | + |
| 78 | + /** \brief Return true if the intermediate states generated along motions are to be added to the tree itself |
| 79 | + */ |
| 80 | + bool getIntermediateStates() const |
| 81 | + { |
| 82 | + return addIntermediateStates_; |
| 83 | + } |
| 84 | + |
| 85 | + /** \brief Specify whether the intermediate states generated along motions are to be added to the tree |
| 86 | + * itself */ |
| 87 | + void setIntermediateStates(bool addIntermediateStates) |
| 88 | + { |
| 89 | + addIntermediateStates_ = addIntermediateStates; |
| 90 | + } |
| 91 | + |
| 92 | + /** \brief Set the range the planner is supposed to use. |
| 93 | +
|
| 94 | + This parameter greatly influences the runtime of the |
| 95 | + algorithm. It represents the maximum length of a |
| 96 | + motion to be added in the tree of motions. */ |
| 97 | + void setRange(double distance) |
| 98 | + { |
| 99 | + maxDistance_ = distance; |
| 100 | + } |
| 101 | + |
| 102 | + /** \brief Get the range the planner is using */ |
| 103 | + double getRange() const |
| 104 | + { |
| 105 | + return maxDistance_; |
| 106 | + } |
| 107 | + |
| 108 | + void setFoundPath(const base::PathPtr &p) |
| 109 | + { |
| 110 | + foundPath = p; |
| 111 | + } |
| 112 | + |
| 113 | + base::PathPtr getFoundPath() const |
| 114 | + { |
| 115 | + return foundPath; |
| 116 | + } |
| 117 | + |
| 118 | + /** \brief Set a different nearest neighbors datastructure */ |
| 119 | + template <template <typename T> class NN> |
| 120 | + void setNearestNeighbors() |
| 121 | + { |
| 122 | + if ((tStart_ && tStart_->size() != 0) || (tGoal_ && tGoal_->size() != 0)) |
| 123 | + OMPL_WARN("Calling setNearestNeighbors will clear all states."); |
| 124 | + clear(); |
| 125 | + tStart_ = std::make_shared<NN<Motion *>>(); |
| 126 | + tGoal_ = std::make_shared<NN<Motion *>>(); |
| 127 | + setup(); |
| 128 | + } |
| 129 | + |
| 130 | + void setup() override; |
| 131 | + |
| 132 | + void setPathCost(double pc); |
| 133 | + |
| 134 | + void freeMemoryPublic(); |
| 135 | + |
| 136 | + protected: |
| 137 | + /** \brief Representation of a motion */ |
| 138 | + class Motion |
| 139 | + { |
| 140 | + public: |
| 141 | + Motion() = default; |
| 142 | + |
| 143 | + Motion(const base::SpaceInformationPtr &si) : state(si->allocState()) |
| 144 | + { |
| 145 | + } |
| 146 | + |
| 147 | + ~Motion() = default; |
| 148 | + |
| 149 | + const base::State *root{nullptr}; |
| 150 | + base::State *state{nullptr}; |
| 151 | + Motion *parent{nullptr}; |
| 152 | + double cost{0}; |
| 153 | + bool connecting{false}; |
| 154 | + }; |
| 155 | + |
| 156 | + /** \brief A nearest-neighbor datastructure representing a tree of motions */ |
| 157 | + using TreeData = std::shared_ptr<NearestNeighbors<Motion *>>; |
| 158 | + |
| 159 | + /** \brief Information attached to growing a tree of motions (used internally) */ |
| 160 | + struct TreeGrowingInfo |
| 161 | + { |
| 162 | + base::State *xstate; |
| 163 | + Motion *xmotion; |
| 164 | + bool start; |
| 165 | + }; |
| 166 | + |
| 167 | + /** \brief The state of the tree after an attempt to extend it */ |
| 168 | + enum GrowState |
| 169 | + { |
| 170 | + /// no progress has been made |
| 171 | + TRAPPED, |
| 172 | + /// progress has been made towards the randomly sampled state |
| 173 | + ADVANCED, |
| 174 | + /// the randomly sampled state was reached |
| 175 | + REACHED |
| 176 | + }; |
| 177 | + |
| 178 | + /** \brief Free the memory allocated by this planner */ |
| 179 | + void freeMemory(); |
| 180 | + |
| 181 | + /** \brief Compute distance between motions (actually distance between contained states) */ |
| 182 | + double distanceFunction(const Motion *a, const Motion *b) const |
| 183 | + { |
| 184 | + auto space_diff = si_->distance(a->state, b->state); |
| 185 | + auto cost_diff = a->cost - b->cost; |
| 186 | + |
| 187 | + auto dist = sqrt(pow(space_diff, 2) + pow(cost_diff, 2)); |
| 188 | + |
| 189 | + return dist; |
| 190 | + } |
| 191 | + |
| 192 | + /** \brief Grow a tree towards a random state */ |
| 193 | + GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion); |
| 194 | + |
| 195 | + /** \brief State sampler */ |
| 196 | + base::InformedSamplerPtr sampler_; |
| 197 | + |
| 198 | + /** \brief The start tree */ |
| 199 | + TreeData tStart_; |
| 200 | + |
| 201 | + /** \brief The goal tree */ |
| 202 | + TreeData tGoal_; |
| 203 | + |
| 204 | + base::State *startState{nullptr}; |
| 205 | + base::State *goalState{nullptr}; |
| 206 | + |
| 207 | + /** \brief A flag that toggles between expanding the start tree (true) or goal tree (false). */ |
| 208 | + bool startTree_{true}; |
| 209 | + |
| 210 | + /** \brief The maximum length of a motion to be added to a tree */ |
| 211 | + double maxDistance_{0.}; |
| 212 | + |
| 213 | + /** \brief Flag indicating whether intermediate states are added to the built tree of motions */ |
| 214 | + bool addIntermediateStates_; |
| 215 | + |
| 216 | + /** \brief The random number generator */ |
| 217 | + RNG rng_; |
| 218 | + |
| 219 | + /** \brief The pair of states in each tree connected during planning. Used for PlannerData computation */ |
| 220 | + std::pair<base::State *, base::State *> connectionPoint_; |
| 221 | + |
| 222 | + /** \brief Distance between the nearest pair of start tree and goal tree nodes. */ |
| 223 | + double distanceBetweenTrees_; |
| 224 | + |
| 225 | + /** \brief Best cost found so far by algorithm */ |
| 226 | + base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()}; |
| 227 | + |
| 228 | + base::PathPtr foundPath{nullptr}; |
| 229 | + |
| 230 | + base::PlannerTerminationCondition _ptc{nullptr}; |
| 231 | + |
| 232 | + /** \brief Objective we're optimizing */ |
| 233 | + base::OptimizationObjectivePtr opt_; |
| 234 | + }; |
| 235 | + } // namespace geometric |
| 236 | +} // namespace ompl |
| 237 | + |
| 238 | +#endif |
0 commit comments