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/geometric/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), simplifyTime_(0.0), lastStatus_(base::PlannerStatus::UNKNOWN)
47 {
48  si_ = si;
49  pdef_ = std::make_shared<base::ProblemDefinition>(si_);
50 }
51 
53  : configured_(false), planTime_(0.0), simplifyTime_(0.0), lastStatus_(base::PlannerStatus::UNKNOWN)
54 {
55  si_ = std::make_shared<base::SpaceInformation>(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  configured_ = true;
79  }
80 }
81 
83 {
84  if (planner_)
85  planner_->clear();
86  if (pdef_)
87  pdef_->clearSolutionPaths();
88 }
89 
91  const base::ScopedState<> &goal, const double threshold)
92 {
93  pdef_->setStartAndGoalStates(start, goal, threshold);
94 
95  // Clear any past solutions since they no longer correspond to our start and goal states
96  pdef_->clearSolutionPaths();
97 
98  psk_ = std::make_shared<PathSimplifier>(si_, pdef_->getGoal());
99 }
100 
101 void ompl::geometric::SimpleSetup::setGoalState(const base::ScopedState<> &goal, const double threshold)
102 {
103  pdef_->setGoalState(goal, threshold);
104  psk_ = std::make_shared<PathSimplifier>(si_, pdef_->getGoal());
105 }
106 
110 {
111  pdef_->setGoal(goal);
112 
113  if (goal && goal->hasType(base::GOAL_SAMPLEABLE_REGION))
114  psk_ = std::make_shared<PathSimplifier>(si_, pdef_->getGoal());
115  else
116  psk_ = std::make_shared<PathSimplifier>(si_);
117 }
118 
119 // we provide a duplicate implementation here to allow the planner to choose how the time is turned into a planner
120 // termination condition
122 {
123  setup();
125  time::point start = time::now();
126  lastStatus_ = planner_->solve(time);
127  planTime_ = time::seconds(time::now() - start);
128  if (lastStatus_)
129  OMPL_INFORM("Solution found in %f seconds", planTime_);
130  else
131  OMPL_INFORM("No solution found after %f seconds", planTime_);
132  return lastStatus_;
133 }
134 
136 {
137  setup();
139  time::point start = time::now();
140  lastStatus_ = planner_->solve(ptc);
141  planTime_ = time::seconds(time::now() - start);
142  if (lastStatus_)
143  OMPL_INFORM("Solution found in %f seconds", planTime_);
144  else
145  OMPL_INFORM("No solution found after %f seconds", planTime_);
146  return lastStatus_;
147 }
148 
150 {
151  if (pdef_)
152  {
153  const base::PathPtr &p = pdef_->getSolutionPath();
154  if (p)
155  {
156  time::point start = time::now();
157  PathGeometric &path = static_cast<PathGeometric &>(*p);
158  std::size_t numStates = path.getStateCount();
159  psk_->simplify(path, ptc);
161  OMPL_INFORM("SimpleSetup: Path simplification took %f seconds and changed from %d to %d states",
162  simplifyTime_, numStates, path.getStateCount());
163  return;
164  }
165  }
166  OMPL_WARN("No solution to simplify");
167 }
168 
170 {
171  if (pdef_)
172  {
173  const base::PathPtr &p = pdef_->getSolutionPath();
174  if (p)
175  {
176  time::point start = time::now();
177  PathGeometric &path = static_cast<PathGeometric &>(*p);
178  std::size_t numStates = path.getStateCount();
179  if (duration < std::numeric_limits<double>::epsilon())
180  psk_->simplifyMax(static_cast<PathGeometric &>(*p));
181  else
182  psk_->simplify(static_cast<PathGeometric &>(*p), duration);
184  OMPL_INFORM("SimpleSetup: Path simplification took %f seconds and changed from %d to %d states",
185  simplifyTime_, numStates, path.getStateCount());
186  return;
187  }
188  }
189  OMPL_WARN("No solution to simplify");
190 }
191 
193 {
194  if (pdef_)
195  {
196  const ompl::base::PathPtr path; // convert to a generic path ptr
197  ompl::base::PlannerSolution solution(path); // a dummy solution
198 
199  // Get our desired solution
200  pdef_->getSolution(solution);
201  return solution.plannerName_;
202  }
203  throw Exception("No problem definition found");
204 }
205 
207 {
208  if (pdef_)
209  {
210  const base::PathPtr &p = pdef_->getSolutionPath();
211  if (p)
212  return static_cast<PathGeometric &>(*p);
213  }
214  throw Exception("No solution path");
215 }
216 
218 {
219  return haveSolutionPath() && (!pdef_->hasApproximateSolution() ||
220  pdef_->getSolutionDifference() < std::numeric_limits<double>::epsilon());
221 }
222 
224 {
225  pd.clear();
226  if (planner_)
227  planner_->getPlannerData(pd);
228 }
229 
230 void ompl::geometric::SimpleSetup::print(std::ostream &out) const
231 {
232  if (si_)
233  {
234  si_->printProperties(out);
235  si_->printSettings(out);
236  }
237  if (planner_)
238  {
239  planner_->printProperties(out);
240  planner_->printSettings(out);
241  }
242  if (pdef_)
243  pdef_->print(out);
244 }
const std::string getSolutionPlannerName() const
Get the best solution&#39;s planer name. Throw an exception if no solution is available.
bool haveExactSolutionPath() const
Return true if a solution path is available (previous call to solve() was successful) and the solutio...
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
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.cpp:90
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:140
double simplifyTime_
The amount of time the last path simplification step took.
Definition: SimpleSetup.h:295
base::PlannerAllocator pa_
The optional planner allocator.
Definition: SimpleSetup.h:283
PathGeometric & getSolutionPath() const
Get the solution path. Throw an exception if no solution is available.
Representation of a solution to a planning problem.
Definition of a scoped state.
Definition: ScopedState.h:56
A shared pointer wrapper for ompl::base::StateSpace.
std::size_t getStateCount() const
Get the number of states (way-points) that make up this path.
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
void setGoal(const base::GoalPtr &goal)
Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called...
base::SpaceInformationPtr si_
The created space information.
Definition: SimpleSetup.h:274
PathSimplifierPtr psk_
The instance of the path simplifier.
Definition: SimpleSetup.h:286
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition: Time.h:76
A shared pointer wrapper for ompl::base::Planner.
SimpleSetup(const base::SpaceInformationPtr &si)
Constructor needs the state space used for planning.
Definition: SimpleSetup.cpp:45
base::PlannerPtr planner_
The maintained planner instance.
Definition: SimpleSetup.h:280
base::ProblemDefinitionPtr pdef_
The created problem definition.
Definition: SimpleSetup.h:277
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
A shared pointer wrapper for ompl::base::SpaceInformation.
virtual void clear()
Clears the entire data structure.
Definition: PlannerData.cpp:74
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
virtual void setup()
This method will create the necessary classes for planning. The solve() method will call this functio...
Definition: SimpleSetup.cpp:59
static base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SelfConfig.cpp:243
void getPlannerData(base::PlannerData &pd) const
Get information about the exploration data structure the motion planner used.
The exception type for ompl.
Definition: Exception.h:46
base::PlannerStatus lastStatus_
The status of the last planning request.
Definition: SimpleSetup.h:298
const base::GoalPtr & getGoal() const
Get the current goal definition.
Definition: SimpleSetup.h:99
virtual base::PlannerStatus solve(double time=1.0)
Run the planner for up to a specified amount of time (default is 1 second)
point now()
Get the current time point.
Definition: Time.h:70
std::string plannerName_
Name of planner type that generated this solution, as received from Planner::getName() ...
bool configured_
Flag indicating whether the classes needed for planning are set up.
Definition: SimpleSetup.h:289
virtual void print(std::ostream &out=std::cout) const
Print information about the current setup.
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.
double planTime_
The amount of time the last planning step took.
Definition: SimpleSetup.h:292
void simplifySolution(double duration=0.0)
Attempt to simplify the current solution path. Spent at most duration seconds in the simplification p...
A shared pointer wrapper for ompl::base::Goal.
Definition of a geometric path.
Definition: PathGeometric.h:60
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: Time.h:64
OMPL_DEPRECATED base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SimpleSetup.cpp:40
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:82
A shared pointer wrapper for ompl::base::Path.
This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible...
Definition: GoalTypes.h:56
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68