SelfConfig.cpp
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Rice University.
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 Rice University 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 #include "ompl/tools/config/SelfConfig.h"
38 #include "ompl/tools/config/MagicConstants.h"
39 #include "ompl/geometric/planners/rrt/RRTConnect.h"
40 #include "ompl/geometric/planners/rrt/RRT.h"
41 #include "ompl/geometric/planners/kpiece/LBKPIECE1.h"
42 #include "ompl/geometric/planners/kpiece/KPIECE1.h"
43 #include "ompl/control/planners/rrt/RRT.h"
44 #include "ompl/control/planners/kpiece/KPIECE1.h"
45 #include "ompl/util/Console.h"
46 #include <boost/thread/mutex.hpp>
47 #include <boost/shared_ptr.hpp>
48 #include <boost/weak_ptr.hpp>
49 #include <algorithm>
50 #include <limits>
51 #include <cmath>
52 #include <map>
53 
55 namespace ompl
56 {
57  namespace tools
58  {
59 
60  class SelfConfig::SelfConfigImpl
61  {
62  friend class SelfConfig;
63 
64  public:
65 
66  SelfConfigImpl(const base::SpaceInformationPtr &si) :
67  wsi_(si), probabilityOfValidState_(-1.0), averageValidMotionLength_(-1.0)
68  {
69  }
70 
72  {
73  base::SpaceInformationPtr si = wsi_.lock();
74  checkSetup(si);
75  if (si && probabilityOfValidState_ < 0.0)
76  probabilityOfValidState_ = si->probabilityOfValidState(magic::TEST_STATE_COUNT);
77  return probabilityOfValidState_;
78  }
79 
81  {
82  base::SpaceInformationPtr si = wsi_.lock();
83  checkSetup(si);
84  if (si && averageValidMotionLength_ < 0.0)
85  averageValidMotionLength_ = si->averageValidMotionLength(magic::TEST_STATE_COUNT);
86  return averageValidMotionLength_;
87  }
88 
89  void configureValidStateSamplingAttempts(unsigned int &attempts)
90  {
91  if (attempts == 0)
93  }
94 
95  void configurePlannerRange(double &range, const std::string &context)
96  {
97  if (range < std::numeric_limits<double>::epsilon())
98  {
99  base::SpaceInformationPtr si = wsi_.lock();
100  if (si)
101  {
102  range = si->getMaximumExtent() * magic::MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION;
103  OMPL_DEBUG("%sPlanner range detected to be %lf", context.c_str(), range);
104  }
105  else
106  OMPL_ERROR("%sUnable to detect planner range. SpaceInformation instance has expired.", context.c_str());
107  }
108  }
109 
110  void configureProjectionEvaluator(base::ProjectionEvaluatorPtr &proj, const std::string &context)
111  {
112  base::SpaceInformationPtr si = wsi_.lock();
113  checkSetup(si);
114  if (!proj && si)
115  {
116  OMPL_INFORM("%sAttempting to use default projection.", context.c_str());
117  proj = si->getStateSpace()->getDefaultProjection();
118  }
119  if (!proj)
120  throw Exception("No projection evaluator specified");
121  proj->setup();
122  }
123 
124  void print(std::ostream &out) const
125  {
126  base::SpaceInformationPtr si = wsi_.lock();
127  if (si)
128  {
129  out << "Configuration parameters for space '" << si->getStateSpace()->getName() << "'" << std::endl;
130  out << " - probability of a valid state is " << probabilityOfValidState_ << std::endl;
131  out << " - average length of a valid motion is " << averageValidMotionLength_ << std::endl;
132  }
133  else
134  out << "EXPIRED" << std::endl;
135  }
136 
137  bool expired() const
138  {
139  return wsi_.expired();
140  }
141 
142  private:
143 
144  void checkSetup(const base::SpaceInformationPtr &si)
145  {
146  if (si)
147  {
148  if (!si->isSetup())
149  {
150  si->setup();
151  probabilityOfValidState_ = -1.0;
152  averageValidMotionLength_ = -1.0;
153  }
154  }
155  else
156  {
157  probabilityOfValidState_ = -1.0;
158  averageValidMotionLength_ = -1.0;
159  }
160  }
161 
162  // we store weak pointers so that the SpaceInformation instances are not kept in
163  // memory until termination of the program due to the use of a static ConfigMap below
164  boost::weak_ptr<base::SpaceInformation> wsi_;
165 
166  double probabilityOfValidState_;
167  double averageValidMotionLength_;
168 
169  boost::mutex lock_;
170  };
171 
172  }
173 }
174 
176 
177 ompl::tools::SelfConfig::SelfConfig(const base::SpaceInformationPtr &si, const std::string &context) :
178  context_(context.empty() ? "" : context + ": ")
179 {
180  typedef std::map<base::SpaceInformation*, boost::shared_ptr<SelfConfigImpl> > ConfigMap;
181 
182  static ConfigMap SMAP;
183  static boost::mutex LOCK;
184 
185  boost::mutex::scoped_lock smLock(LOCK);
186 
187  // clean expired entries from the map
188  ConfigMap::iterator dit = SMAP.begin();
189  while (dit != SMAP.end())
190  {
191  if (dit->second->expired())
192  SMAP.erase(dit++);
193  else
194  ++dit;
195  }
196 
197  ConfigMap::const_iterator it = SMAP.find(si.get());
198 
199  if (it != SMAP.end())
200  impl_ = it->second.get();
201  else
202  {
203  impl_ = new SelfConfigImpl(si);
204  SMAP[si.get()].reset(impl_);
205  }
206 }
207 
208 ompl::tools::SelfConfig::~SelfConfig()
209 {
210 }
211 
212 /* ------------------------------------------------------------------------ */
213 
215 {
216  boost::mutex::scoped_lock iLock(impl_->lock_);
217  return impl_->getProbabilityOfValidState();
218 }
219 
221 {
222  boost::mutex::scoped_lock iLock(impl_->lock_);
223  return impl_->getAverageValidMotionLength();
224 }
225 
227 {
228  boost::mutex::scoped_lock iLock(impl_->lock_);
229  impl_->configureValidStateSamplingAttempts(attempts);
230 }
231 
233 {
234  boost::mutex::scoped_lock iLock(impl_->lock_);
235  impl_->configurePlannerRange(range, context_);
236 }
237 
239 {
240  boost::mutex::scoped_lock iLock(impl_->lock_);
241  return impl_->configureProjectionEvaluator(proj, context_);
242 }
243 
244 void ompl::tools::SelfConfig::print(std::ostream &out) const
245 {
246  boost::mutex::scoped_lock iLock(impl_->lock_);
247  impl_->print(out);
248 }
249 
251 {
252  base::PlannerPtr planner;
253  if (!goal)
254  throw Exception("Unable to allocate default planner for unspecified goal definition");
255 
256  base::SpaceInformationPtr si(goal->getSpaceInformation());
257  control::SpaceInformationPtr siC(boost::dynamic_pointer_cast<control::SpaceInformation, base::SpaceInformation>(si));
258  if (siC) // kinodynamic planning
259  {
260  // if we have a default projection
261  if (siC->getStateSpace()->hasDefaultProjection())
262  planner = base::PlannerPtr(new control::KPIECE1(siC));
263  // otherwise use a single-tree planner
264  else
265  planner = base::PlannerPtr(new control::RRT(siC));
266  }
267  // if we can sample the goal region, use a bi-directional planner
268  else if (goal->hasType(base::GOAL_SAMPLEABLE_REGION))
269  {
270  // if we have a default projection
271  if (goal->getSpaceInformation()->getStateSpace()->hasDefaultProjection())
272  planner = base::PlannerPtr(new geometric::LBKPIECE1(goal->getSpaceInformation()));
273  else
274  planner = base::PlannerPtr(new geometric::RRTConnect(goal->getSpaceInformation()));
275  }
276  // otherwise use a single-tree planner
277  else
278  {
279  // if we have a default projection
280  if (goal->getSpaceInformation()->getStateSpace()->hasDefaultProjection())
281  planner = base::PlannerPtr(new geometric::KPIECE1(goal->getSpaceInformation()));
282  else
283  planner = base::PlannerPtr(new geometric::RRT(goal->getSpaceInformation()));
284  }
285 
286  if (!planner)
287  throw Exception("Unable to allocate default planner");
288 
289  return planner;
290 }
void print(std::ostream &out=std::cout) const
Print the computed configuration parameters.
Definition: SelfConfig.cpp:244
Main namespace. Contains everything in this library.
Definition: Cost.h:42
A boost shared pointer wrapper for ompl::base::Planner.
Kinematic Planning by Interior-Exterior Cell Exploration.
Definition: KPIECE1.h:74
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
double getAverageValidMotionLength()
Get the probability of a sampled state being valid (calls base::SpaceInformation::averageValidMotionL...
Definition: SelfConfig.cpp:220
RRT-Connect (RRTConnect)
Definition: RRTConnect.h:61
A boost shared pointer wrapper for ompl::base::ProjectionEvaluator.
Rapidly-exploring Random Trees.
Definition: RRT.h:65
A boost shared pointer wrapper for ompl::base::SpaceInformation.
SelfConfig(const base::SpaceInformationPtr &si, const std::string &context=std::string())
Construct an instance that can configure the space encapsulated by si. Any information printed to the...
Definition: SelfConfig.cpp:177
Kinodynamic Planning by Interior-Exterior Cell Exploration.
Definition: KPIECE1.h:77
A boost shared pointer wrapper for ompl::control::SpaceInformation.
Lazy Bi-directional KPIECE with one level of discretization.
Definition: LBKPIECE1.h:78
static base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SelfConfig.cpp:250
The exception type for ompl.
Definition: Exception.h:47
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition: Console.h:70
void configureProjectionEvaluator(base::ProjectionEvaluatorPtr &proj)
If proj is undefined, it is set to the default projection reported by base::StateSpace::getDefaultPro...
Definition: SelfConfig.cpp:238
double getProbabilityOfValidState()
Get the probability of a sampled state being valid (calls base::SpaceInformation::probabilityOfValidS...
Definition: SelfConfig.cpp:214
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition: SelfConfig.cpp:232
Rapidly-exploring Random Tree.
Definition: RRT.h:66
static const unsigned int TEST_STATE_COUNT
When multiple states need to be generated as part of the computation of various information (usually ...
static const double MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION
For planners: if default values are to be used for the maximum length of motions, this constant defin...
A boost shared pointer wrapper for ompl::base::Goal.
void configureValidStateSamplingAttempts(unsigned int &attempts)
Instances of base::ValidStateSampler need a number of attempts to be specified – the maximum number ...
Definition: SelfConfig.cpp:226
static const unsigned int MAX_VALID_SAMPLE_ATTEMPTS
When multiple attempts are needed to generate valid samples, this value defines the default number of...
This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible...
Definition: GoalTypes.h:55
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68