SimpleSetup.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, 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 #ifndef OMPL_CONTROL_SIMPLE_SETUP_
38 #define OMPL_CONTROL_SIMPLE_SETUP_
39 
40 #include "ompl/base/Planner.h"
41 #include "ompl/control/SpaceInformation.h"
42 #include "ompl/control/PlannerData.h"
43 #include "ompl/base/ProblemDefinition.h"
44 #include "ompl/control/PathControl.h"
45 #include "ompl/geometric/PathGeometric.h"
46 #include "ompl/util/Console.h"
47 #include "ompl/util/Exception.h"
48 #include "ompl/util/Deprecation.h"
49 
50 namespace ompl
51 {
52  namespace control
53  {
55  OMPL_CLASS_FORWARD(SimpleSetup);
57 
63  class SimpleSetup
64  {
65  public:
67  explicit SimpleSetup(const SpaceInformationPtr &si);
68 
70  explicit SimpleSetup(const ControlSpacePtr &space);
71 
72  virtual ~SimpleSetup() = default;
73 
76  {
77  return si_;
78  }
79 
81  const base::ProblemDefinitionPtr &getProblemDefinition() const
82  {
83  return pdef_;
84  }
85 
87  base::ProblemDefinitionPtr &getProblemDefinition()
88  {
89  return pdef_;
90  }
91 
93  const base::StateSpacePtr &getStateSpace() const
94  {
95  return si_->getStateSpace();
96  }
97 
99  const ControlSpacePtr &getControlSpace() const
100  {
101  return si_->getControlSpace();
102  }
103 
105  const base::StateValidityCheckerPtr &getStateValidityChecker() const
106  {
107  return si_->getStateValidityChecker();
108  }
109 
112  {
113  return si_->getStatePropagator();
114  }
115 
117  const base::GoalPtr &getGoal() const
118  {
119  return pdef_->getGoal();
120  }
121 
123  const base::PlannerPtr &getPlanner() const
124  {
125  return planner_;
126  }
127 
130  {
131  return pa_;
132  }
133 
136  bool haveExactSolutionPath() const;
137 
140  bool haveSolutionPath() const
141  {
142  return pdef_->getSolutionPath() != nullptr;
143  }
144 
146  PathControl &getSolutionPath() const;
147 
149  void getPlannerData(base::PlannerData &pd) const;
150 
152  void setStateValidityChecker(const base::StateValidityCheckerPtr &svc)
153  {
154  si_->setStateValidityChecker(svc);
155  }
156 
159  {
160  si_->setStateValidityChecker(svc);
161  }
162 
164  void setStatePropagator(const StatePropagatorFn &sp)
165  {
166  si_->setStatePropagator(sp);
167  }
168 
170  void setStatePropagator(const StatePropagatorPtr &sp)
171  {
172  si_->setStatePropagator(sp);
173  }
174 
176  void setOptimizationObjective(const base::OptimizationObjectivePtr &optimizationObjective)
177  {
178  pdef_->setOptimizationObjective(optimizationObjective);
179  }
180 
182  void setStartAndGoalStates(const base::ScopedState<> &start, const base::ScopedState<> &goal,
183  const double threshold = std::numeric_limits<double>::epsilon())
184  {
185  pdef_->setStartAndGoalStates(start, goal, threshold);
186  }
187 
189  void setGoalState(const base::ScopedState<> &goal,
190  const double threshold = std::numeric_limits<double>::epsilon())
191  {
192  pdef_->setGoalState(goal, threshold);
193  }
194 
197  void addStartState(const base::ScopedState<> &state)
198  {
199  pdef_->addStartState(state);
200  }
201 
203  void clearStartStates()
204  {
205  pdef_->clearStartStates();
206  }
207 
209  void setStartState(const base::ScopedState<> &state)
210  {
212  addStartState(state);
213  }
214 
217  void setGoal(const base::GoalPtr &goal)
218  {
219  pdef_->setGoal(goal);
220  }
221 
226  void setPlanner(const base::PlannerPtr &planner)
227  {
228  if (planner && planner->getSpaceInformation().get() != si_.get())
229  throw Exception("Planner instance does not match space information");
230  planner_ = planner;
231  configured_ = false;
232  }
233 
238  {
239  pa_ = pa;
240  planner_.reset();
241  configured_ = false;
242  }
243 
245  virtual base::PlannerStatus solve(double time = 1.0);
246 
249 
252  {
253  return last_status_;
254  }
255 
257  double getLastPlanComputationTime() const
258  {
259  return planTime_;
260  }
261 
265  virtual void clear();
266 
268  virtual void print(std::ostream &out = std::cout) const;
269 
273  virtual void setup();
274 
275  protected:
278 
280  base::ProblemDefinitionPtr pdef_;
281 
283  base::PlannerPtr planner_;
284 
287 
289  bool configured_;
290 
292  double planTime_;
293 
296  };
297 
300  OMPL_DEPRECATED base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal);
301  }
302 }
303 #endif
const base::PlannerAllocator & getPlannerAllocator() const
Get the planner allocator.
Definition: SimpleSetup.h:190
void setOptimizationObjective(const base::OptimizationObjectivePtr &optimizationObjective)
Set the optimization objective to use.
Definition: SimpleSetup.h:237
const ControlSpacePtr & getControlSpace() const
Get the current instance of the control space.
Definition: SimpleSetup.h:160
A shared pointer wrapper for ompl::base::SpaceInformation.
const base::StateValidityCheckerPtr & getStateValidityChecker() const
Get the current instance of the state validity checker.
Definition: SimpleSetup.h:166
SimpleSetup(const SpaceInformationPtr &si)
Constructor needs the control space used for planning.
Definition: SimpleSetup.cpp:44
A shared pointer wrapper for ompl::control::ControlSpace.
const SpaceInformationPtr & getSpaceInformation() const
Get the current instance of the space information.
Definition: SimpleSetup.h:136
base::ProblemDefinitionPtr pdef_
The created problem definition.
Definition: SimpleSetup.h:341
void setPlannerAllocator(const base::PlannerAllocator &pa)
Set the planner allocator to use. This is only used if no planner has been set. This is optional – a ...
Definition: SimpleSetup.h:298
SpaceInformationPtr si_
The created space information.
Definition: SimpleSetup.h:338
const base::GoalPtr & getGoal() const
Get the current goal definition.
Definition: SimpleSetup.h:178
void setPlanner(const base::PlannerPtr &planner)
Set the planner to use. If the planner is not set, an attempt is made to use the planner allocator....
Definition: SimpleSetup.h:287
void setStartState(const base::ScopedState<> &state)
Clear the currently set starting states and add state as the starting state.
Definition: SimpleSetup.h:270
OMPL_DEPRECATED base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SimpleSetup.cpp:39
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:235
std::function< void(const base::State *, const Control *, const double, base::State *)> StatePropagatorFn
A function that achieves state propagation.
base::PlannerAllocator pa_
The optional planner allocator.
Definition: SimpleSetup.h:347
void getPlannerData(base::PlannerData &pd) const
Get information about the exploration data structure the motion planner used.
void setStartAndGoalStates(const base::ScopedState<> &start, const base::ScopedState<> &goal, const double threshold=std::numeric_limits< double >::epsilon())
Set the start and goal states to use.
Definition: SimpleSetup.h:243
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
double planTime_
The amount of time the last planning step took.
Definition: SimpleSetup.h:353
virtual void setup()
This method will create the necessary classes for planning. The solve() method will call this functio...
Definition: SimpleSetup.cpp:58
bool configured_
Flag indicating whether the classes needed for planning are set up.
Definition: SimpleSetup.h:350
A class to store the exit status of Planner::solve()
std::function< PlannerPtr(const SpaceInformationPtr &)> PlannerAllocator
Definition of a function that can allocate a planner.
Definition: Planner.h:506
virtual base::PlannerStatus solve(double time=1.0)
Run the planner for a specified amount of time (default is 1 second)
Definition: SimpleSetup.cpp:92
void setGoalState(const base::ScopedState<> &goal, const double threshold=std::numeric_limits< double >::epsilon())
A simple form of setGoal(). The goal will be an instance of ompl::base::GoalState.
Definition: SimpleSetup.h:250
const base::ProblemDefinitionPtr & getProblemDefinition() const
Get the current instance of the problem definition.
Definition: SimpleSetup.h:142
void clearStartStates()
Clear the currently set starting states.
Definition: SimpleSetup.h:264
const base::PlannerPtr & getPlanner() const
Get the current planner.
Definition: SimpleSetup.h:184
base::PlannerStatus getLastPlannerStatus() const
Return the status of the last planning attempt.
Definition: SimpleSetup.h:312
PathControl & getSolutionPath() const
Get the solution path. Throw an exception if no solution is available.
base::PlannerPtr planner_
The maintained planner instance.
Definition: SimpleSetup.h:344
std::function< bool(const State *)> StateValidityCheckerFn
If no state validity checking class is specified (StateValidityChecker), a std::function can be speci...
A shared pointer wrapper for ompl::control::StatePropagator.
Definition of a control path.
Definition: PathControl.h:90
void addStartState(const base::ScopedState<> &state)
Add a starting state for planning. This call is not needed if setStartAndGoalStates() has been called...
Definition: SimpleSetup.h:258
void setGoal(const base::GoalPtr &goal)
Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called.
Definition: SimpleSetup.h:278
bool haveSolutionPath() const
Return true if a solution path is available (previous call to solve() was successful)....
Definition: SimpleSetup.h:201
void setStatePropagator(const StatePropagatorFn &sp)
Set the function that performs state propagation.
Definition: SimpleSetup.h:225
Definition of a scoped state.
Definition: ScopedState.h:117
const StatePropagatorPtr & getStatePropagator() const
Get the instance of the state propagator being used.
Definition: SimpleSetup.h:172
The exception type for ompl.
Definition: Exception.h:76
base::PlannerStatus last_status_
The status of the last planning request.
Definition: SimpleSetup.h:356
void setStateValidityChecker(const base::StateValidityCheckerPtr &svc)
Set the state validity checker to use.
Definition: SimpleSetup.h:213
bool haveExactSolutionPath() const
Return true if a solution path is available (previous call to solve() was successful) and the solutio...
double getLastPlanComputationTime() const
Get the amount of time (in seconds) spent during the last planning step.
Definition: SimpleSetup.h:318
virtual void print(std::ostream &out=std::cout) const
Print information about the current setup.
virtual void clear()
Clear all planning data. This only includes data generated by motion plan computation....
Definition: SimpleSetup.cpp:82
Main namespace. Contains everything in this library.
Definition: AppBase.h:20
const base::StateSpacePtr & getStateSpace() const
Get the current instance of the state space.
Definition: SimpleSetup.h:154