Loading...
Searching...
No Matches
OptimizePlan.cpp
1/*********************************************************************
2* Software License Agreement (BSD License)
3*
4* Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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/tools/multiplan/OptimizePlan.h"
38#include "ompl/geometric/PathSimplifier.h"
39#include "ompl/base/OptimizationObjective.h"
40
41void ompl::tools::OptimizePlan::addPlanner(const base::PlannerPtr &planner)
42{
43 if (planner && planner->getSpaceInformation().get() != getProblemDefinition()->getSpaceInformation().get())
44 throw Exception("Planner instance does not match space information");
45 planners_.push_back(planner);
46}
47
49{
50 planners_.push_back(pa(getProblemDefinition()->getSpaceInformation()));
51}
52
54{
55 planners_.clear();
56}
57
58ompl::base::PlannerStatus ompl::tools::OptimizePlan::solve(double solveTime, unsigned int maxSol, unsigned int nthreads)
59{
60 time::point end = time::now() + time::seconds(solveTime);
61 unsigned int nt = std::min(nthreads, (unsigned int)planners_.size());
62 OMPL_DEBUG("Using %u threads", nt);
63
65 unsigned int np = 0;
66 const base::ProblemDefinitionPtr &pdef = getProblemDefinition();
67 pp_.clearHybridizationPaths();
68
69 while (time::now() < end)
70 {
71 pp_.clearPlanners();
72 for (unsigned int i = 0; i < nt; ++i)
73 {
74 planners_[np]->clear();
75 pp_.addPlanner(planners_[np]);
76 np = (np + 1) % planners_.size();
77 }
78 base::PlannerStatus localResult = pp_.solve(std::max(time::seconds(end - time::now()), 0.0), true);
79 if (localResult)
80 {
82 result = localResult;
83
84 if (!pdef->hasOptimizationObjective())
85 {
86 OMPL_DEBUG("Terminating early since there is no optimization objective specified");
87 break;
88 }
89
90 base::Cost obj_cost = pdef->getSolutionPath()->cost(pdef->getOptimizationObjective());
91
92 if (pdef->getOptimizationObjective()->isSatisfied(obj_cost))
93 {
94 OMPL_DEBUG("Terminating early since solution path satisfies the optimization objective");
95 break;
96 }
97 if (pdef->getSolutionCount() >= maxSol)
98 {
99 OMPL_DEBUG("Terminating early since %u solutions were generated", maxSol);
100 break;
101 }
102 }
103 }
104
105 // if we have more time, and we have a geometric path, we try to simplify it
106 if (time::now() < end && result)
107 {
108 geometric::PathGeometric *p = dynamic_cast<geometric::PathGeometric *>(pdef->getSolutionPath().get());
109 if (p)
110 {
111 geometric::PathSimplifier ps(getProblemDefinition()->getSpaceInformation());
112 ps.simplify(*p, std::max(time::seconds(end - time::now()), 0.0));
113 }
114 }
115
116 return result;
117}
The exception type for ompl.
Definition Exception.h:47
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Definition of a geometric path.
This class contains routines that attempt to simplify geometric paths.
bool simplify(PathGeometric &path, double maxTime, bool atLeastOnce=true)
Run simplification algorithms on the path for at most maxTime seconds, and at least once if atLeastOn...
void addPlanner(const base::PlannerPtr &planner)
Add a planner to use.
void clearPlanners()
Clear the set of planners to be executed.
const base::ProblemDefinitionPtr & getProblemDefinition() const
Get the problem definition used.
base::PlannerStatus solve(double solveTime, unsigned int maxSol=10, unsigned int nthreads=1)
Try to solve the specified problem within a solveTime seconds, using at most nthreads threads....
void addPlannerAllocator(const base::PlannerAllocator &pa)
Add a planner allocator to use.
std::vector< base::PlannerPtr > planners_
The set of planners to be used.
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition Console.h:70
std::function< PlannerPtr(const SpaceInformationPtr &)> PlannerAllocator
Definition of a function that can allocate a planner.
Definition Planner.h:444
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
A class to store the exit status of Planner::solve()
@ EXACT_SOLUTION
The planner found an exact solution.