All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends
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/control/planners/rrt/RRT.h"
39 #include "ompl/control/planners/kpiece/KPIECE1.h"
40 
42 {
43  base::PlannerPtr planner;
44  if (!goal)
45  throw Exception("Unable to allocate default planner for unspecified goal definition");
46 
47  SpaceInformationPtr si = boost::static_pointer_cast<SpaceInformation, base::SpaceInformation>(goal->getSpaceInformation());
48  if (si->getStateSpace()->hasDefaultProjection())
49  planner = base::PlannerPtr(new KPIECE1(si));
50  else
51  planner = base::PlannerPtr(new RRT(si));
52 
53  return planner;
54 }
55 
57  configured_(false), planTime_(0.0), last_status_(base::PlannerStatus::UNKNOWN)
58 {
59  si_.reset(new SpaceInformation(space->getStateSpace(), space));
60  pdef_.reset(new base::ProblemDefinition(si_));
61  params_.include(si_->params());
62 }
63 
65 {
66  if (!configured_ || !si_->isSetup() || !planner_->isSetup())
67  {
68  if (!si_->isSetup())
69  si_->setup();
70  if (!planner_)
71  {
72  if (pa_)
73  planner_ = pa_(si_);
74  if (!planner_)
75  {
76  OMPL_INFORM("No planner specified. Using default.");
77  planner_ = getDefaultPlanner(getGoal());
78  }
79  }
80  planner_->setProblemDefinition(pdef_);
81  if (!planner_->isSetup())
82  planner_->setup();
83 
84  params_.clear();
85  params_.include(si_->params());
86  params_.include(planner_->params());
87  configured_ = true;
88  }
89 }
90 
92 {
93  if (planner_)
94  planner_->clear();
95  if (pdef_)
96  pdef_->clearSolutionPaths();
97 }
98 
99 // we provide a duplicate implementation here to allow the planner to choose how the time is turned into a planner termination condition
101 {
102  setup();
103  last_status_ = base::PlannerStatus::UNKNOWN;
104  time::point start = time::now();
105  last_status_ = planner_->solve(time);
106  planTime_ = time::seconds(time::now() - start);
107  if (last_status_)
108  OMPL_INFORM("Solution found in %f seconds", planTime_);
109  else
110  OMPL_INFORM("No solution found after %f seconds", planTime_);
111  return last_status_;
112 }
113 
115 {
116  setup();
117  last_status_ = base::PlannerStatus::UNKNOWN;
118  time::point start = time::now();
119  last_status_ = planner_->solve(ptc);
120  planTime_ = time::seconds(time::now() - start);
121  if (last_status_)
122  OMPL_INFORM("Solution found in %f seconds", planTime_);
123  else
124  OMPL_INFORM("No solution found after %f seconds", planTime_);
125  return last_status_;
126 }
127 
129 {
130  if (pdef_)
131  {
132  const base::PathPtr &p = pdef_->getSolutionPath();
133  if (p)
134  return static_cast<PathControl&>(*p);
135  }
136  throw Exception("No solution path");
137 }
138 
140 {
141  return haveSolutionPath() && (!pdef_->hasApproximateSolution() || pdef_->getSolutionDifference() < std::numeric_limits<double>::epsilon());
142 }
143 
145 {
146  pd.clear();
147  if (planner_)
148  planner_->getPlannerData(pd);
149 }
150 
151 void ompl::control::SimpleSetup::print(std::ostream &out) const
152 {
153  if (si_)
154  {
155  si_->printProperties(out);
156  si_->printSettings(out);
157  }
158  if (planner_)
159  {
160  planner_->printProperties(out);
161  planner_->printSettings(out);
162  }
163  if (pdef_)
164  pdef_->print(out);
165 }
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
void include(const ParamSet &other, const std::string &prefix="")
Include the params of a different ParamSet into this one. Optionally include a prefix for each of the...
base::ProblemDefinitionPtr pdef_
The created problem definition.
Definition: SimpleSetup.h:279
base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)
Given a goal specification, decide on a planner for that goal.
Definition: SimpleSetup.cpp:41
virtual void clear(void)
Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected.
Definition: SimpleSetup.cpp:91
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition of a control path.
Definition: PathControl.h:54
SimpleSetup(const ControlSpacePtr &space)
Constructor needs the control space used for planning.
Definition: SimpleSetup.cpp:56
virtual base::PlannerStatus solve(double time=1.0)
Run the planner for a specified amount of time (default is 1 second)
A boost shared pointer wrapper for ompl::control::ControlSpace.
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition: Time.h:62
A boost shared pointer wrapper for ompl::base::Planner.
virtual void setup(void)
This method will create the necessary classes for planning. The solve() method will call this functio...
Definition: SimpleSetup.cpp:64
boost::posix_time::ptime point
Representation of a point in time.
Definition: Time.h:50
base::ParamSet params_
The parameters that describe the planning context.
Definition: SimpleSetup.h:297
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
virtual void print(std::ostream &out=std::cout) const
Print information about the current setup.
The base class for space information. This contains all the information about the space planning is d...
PathControl & getSolutionPath(void) const
Get the solution path. Throw an exception if no solution is available.
void getPlannerData(base::PlannerData &pd) const
Get information about the exploration data structure the motion planner used.
Kinodynamic Planning by Interior-Exterior Cell Exploration.
Definition: KPIECE1.h:77
A boost shared pointer wrapper for ompl::control::SpaceInformation.
SpaceInformationPtr si_
The created space information.
Definition: SimpleSetup.h:276
The exception type for ompl.
Definition: Exception.h:47
Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...
bool haveExactSolutionPath(void) const
Return true if a solution path is available (previous call to solve() was successful) and the solutio...
Rapidly-exploring Random Tree.
Definition: RRT.h:66
A boost shared pointer wrapper for ompl::base::Goal.
virtual void clear(void)
Clears the entire data structure.
Definition: PlannerData.cpp:78
Space information containing necessary information for planning with controls. setup() needs to be ca...
point now(void)
Get the current time point.
Definition: Time.h:56
A boost shared pointer wrapper for ompl::base::Path.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68