RRTConnect.h
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_RRT_CONNECT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_RRT_CONNECT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
42 
43 namespace ompl
44 {
45 
46  namespace geometric
47  {
48 
61  class RRTConnect : public base::Planner
62  {
63  public:
64 
67 
68  virtual ~RRTConnect();
69 
70  virtual void getPlannerData(base::PlannerData &data) const;
71 
73 
74  virtual void clear();
75 
81  void setRange(double distance)
82  {
83  maxDistance_ = distance;
84  }
85 
87  double getRange() const
88  {
89  return maxDistance_;
90  }
91 
93  template<template<typename T> class NN>
95  {
96  tStart_.reset(new NN<Motion*>());
97  tGoal_.reset(new NN<Motion*>());
98  }
99 
100  virtual void setup();
101 
102  protected:
103 
105  class Motion
106  {
107  public:
108 
109  Motion() : root(NULL), state(NULL), parent(NULL)
110  {
111  parent = NULL;
112  state = NULL;
113  }
114 
115  Motion(const base::SpaceInformationPtr &si) : root(NULL), state(si->allocState()), parent(NULL)
116  {
117  }
118 
119  ~Motion()
120  {
121  }
122 
123  const base::State *root;
124  base::State *state;
125  Motion *parent;
126 
127  };
128 
130  typedef boost::shared_ptr< NearestNeighbors<Motion*> > TreeData;
131 
134  {
135  base::State *xstate;
136  Motion *xmotion;
137  bool start;
138  };
139 
142  {
149  };
150 
152  void freeMemory();
153 
155  double distanceFunction(const Motion *a, const Motion *b) const
156  {
157  return si_->distance(a->state, b->state);
158  }
159 
161  GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion);
162 
165 
167  TreeData tStart_;
168 
170  TreeData tGoal_;
171 
173  double maxDistance_;
174 
177 
179  std::pair<base::State*, base::State*> connectionPoint_;
180  };
181 
182  }
183 }
184 
185 #endif
RRTConnect(const base::SpaceInformationPtr &si)
Constructor.
Definition: RRTConnect.cpp:41
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
base::StateSamplerPtr sampler_
State sampler.
Definition: RRTConnect.h:164
TreeData tGoal_
The goal tree.
Definition: RRTConnect.h:170
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRTConnect.h:81
A boost shared pointer wrapper for ompl::base::StateSampler.
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRTConnect.cpp:57
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
no progress has been made
Definition: RRTConnect.h:144
void freeMemory()
Free the memory allocated by this planner.
Definition: RRTConnect.cpp:71
boost::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition: RRTConnect.h:130
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: RRTConnect.h:94
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRTConnect.h:173
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition: RRTConnect.h:179
Main namespace. Contains everything in this library.
Definition: Cost.h:42
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
Representation of a motion.
Definition: RRTConnect.h:105
Base class for a planner.
Definition: Planner.h:232
RRT-Connect (RRTConnect)
Definition: RRTConnect.h:61
double getRange() const
Get the range the planner is using.
Definition: RRTConnect.h:87
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
A boost shared pointer wrapper for ompl::base::SpaceInformation.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRTConnect.h:155
GrowState
The state of the tree after an attempt to extend it.
Definition: RRTConnect.h:141
RNG rng_
The random number generator.
Definition: RRTConnect.h:176
Definition of an abstract state.
Definition: State.h:50
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: RRTConnect.cpp:297
the randomly sampled state was reached
Definition: RRTConnect.h:148
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: RRTConnect.cpp:151
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRTConnect.cpp:98
Information attached to growing a tree of motions (used internally)
Definition: RRTConnect.h:133
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
progress has been made towards the randomly sampled state
Definition: RRTConnect.h:146
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
Definition: RRTConnect.cpp:110
TreeData tStart_
The start tree.
Definition: RRTConnect.h:167