SimpleSetup.cpp
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 #include "ompl/control/SimpleSetup.h"
38 #include "ompl/tools/config/SelfConfig.h"
39 
41 {
42  return tools::SelfConfig::getDefaultPlanner(goal);
43 }
44 
46  : configured_(false), planTime_(0.0), last_status_(base::PlannerStatus::UNKNOWN)
47 {
48  si_ = si;
49  pdef_ = std::make_shared<base::ProblemDefinition>(si_);
50 }
51 
53  : configured_(false), planTime_(0.0), last_status_(base::PlannerStatus::UNKNOWN)
54 {
55  si_ = std::make_shared<SpaceInformation>(space->getStateSpace(), space);
56  pdef_ = std::make_shared<base::ProblemDefinition>(si_);
57 }
58 
60 {
61  if (!configured_ || !si_->isSetup() || !planner_->isSetup())
62  {
63  if (!si_->isSetup())
64  si_->setup();
65  if (!planner_)
66  {
67  if (pa_)
68  planner_ = pa_(si_);
69  if (!planner_)
70  {
71  OMPL_INFORM("No planner specified. Using default.");
73  }
74  }
75  planner_->setProblemDefinition(pdef_);
76  if (!planner_->isSetup())
77  planner_->setup();
78 
79  configured_ = true;
80  }
81 }
82 
84 {
85  if (planner_)
86  planner_->clear();
87  if (pdef_)
88  pdef_->clearSolutionPaths();
89 }
90 
91 // we provide a duplicate implementation here to allow the planner to choose how the time is turned into a planner
92 // termination condition
94 {
95  setup();
97  time::point start = time::now();
98  last_status_ = planner_->solve(time);
99  planTime_ = time::seconds(time::now() - start);
100  if (last_status_)
101  OMPL_INFORM("Solution found in %f seconds", planTime_);
102  else
103  OMPL_INFORM("No solution found after %f seconds", planTime_);
104  return last_status_;
105 }
106 
108 {
109  setup();
111  time::point start = time::now();
112  last_status_ = planner_->solve(ptc);
113  planTime_ = time::seconds(time::now() - start);
114  if (last_status_)
115  OMPL_INFORM("Solution found in %f seconds", planTime_);
116  else
117  OMPL_INFORM("No solution found after %f seconds", planTime_);
118  return last_status_;
119 }
120 
122 {
123  if (pdef_)
124  {
125  const base::PathPtr &p = pdef_->getSolutionPath();
126  if (p)
127  return static_cast<PathControl &>(*p);
128  }
129  throw Exception("No solution path");
130 }
131 
133 {
134  return haveSolutionPath() && (!pdef_->hasApproximateSolution() ||
135  pdef_->getSolutionDifference() < std::numeric_limits<double>::epsilon());
136 }
137 
139 {
140  pd.clear();
141  if (planner_)
142  planner_->getPlannerData(pd);
143 }
144 
145 void ompl::control::SimpleSetup::print(std::ostream &out) const
146 {
147  if (si_)
148  {
149  si_->printProperties(out);
150  si_->printSettings(out);
151  }
152  if (planner_)
153  {
154  planner_->printProperties(out);
155  planner_->printSettings(out);
156  }
157  if (pdef_)
158  pdef_->print(out);
159 }
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
SimpleSetup(const SpaceInformationPtr &si)
Constructor needs the control space used for planning.
Definition: SimpleSetup.cpp:45
base::PlannerAllocator pa_
The optional planner allocator.
Definition: SimpleSetup.h:280
base::ProblemDefinitionPtr pdef_
The created problem definition.
Definition: SimpleSetup.h:274
OMPL_DEPRECATED base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SimpleSetup.cpp:40
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition of a control path.
Definition: PathControl.h:60
base::PlannerPtr planner_
The maintained planner instance.
Definition: SimpleSetup.h:277
virtual base::PlannerStatus solve(double time=1.0)
Run the planner for a specified amount of time (default is 1 second)
Definition: SimpleSetup.cpp:93
virtual void setup()
This method will create the necessary classes for planning. The solve() method will call this functio...
Definition: SimpleSetup.cpp:59
A shared pointer wrapper for ompl::control::ControlSpace.
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition: Time.h:76
virtual void print(std::ostream &out=std::cout) const
Print information about the current setup.
A shared pointer wrapper for ompl::base::Planner.
PathControl & getSolutionPath() const
Get the solution path. Throw an exception if no solution is available.
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
base::PlannerStatus last_status_
The status of the last planning request.
Definition: SimpleSetup.h:289
virtual void clear()
Clears the entire data structure.
Definition: PlannerData.cpp:74
bool haveExactSolutionPath() const
Return true if a solution path is available (previous call to solve() was successful) and the solutio...
A shared pointer wrapper for ompl::control::SpaceInformation.
SpaceInformationPtr si_
The created space information.
Definition: SimpleSetup.h:271
static base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SelfConfig.cpp:243
The exception type for ompl.
Definition: Exception.h:46
void getPlannerData(base::PlannerData &pd) const
Get information about the exploration data structure the motion planner used.
point now()
Get the current time point.
Definition: Time.h:70
double planTime_
The amount of time the last planning step took.
Definition: SimpleSetup.h:286
A shared pointer wrapper for ompl::base::Goal.
const base::GoalPtr & getGoal() const
Get the current goal definition.
Definition: SimpleSetup.h:111
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: Time.h:64
bool haveSolutionPath() const
Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate.
Definition: SimpleSetup.h:134
bool configured_
Flag indicating whether the classes needed for planning are set up.
Definition: SimpleSetup.h:283
virtual void clear()
Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected.
Definition: SimpleSetup.cpp:83
A shared pointer wrapper for ompl::base::Path.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68