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