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