Loading...
Searching...
No Matches
CForest.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, 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/* Authors: Javier V. Gómez, Ioan Sucan, Mark Moll */
36
37#include "ompl/geometric/planners/cforest/CForest.h"
38#include "ompl/geometric/planners/rrt/RRTstar.h"
39#include "ompl/base/objectives/PathLengthOptimizationObjective.h"
40#include "ompl/util/String.h"
41#include <thread>
42
43ompl::geometric::CForest::CForest(const base::SpaceInformationPtr &si) : base::Planner(si, "CForest")
44{
45 specs_.optimizingPaths = true;
46 specs_.multithreaded = true;
47
48 numThreads_ = std::max(std::thread::hardware_concurrency(), 2u);
49 Planner::declareParam<bool>("focus_search", this, &CForest::setFocusSearch, &CForest::getFocusSearch, "0,1");
50 Planner::declareParam<unsigned int>("num_threads", this, &CForest::setNumThreads, &CForest::getNumThreads, "0:64");
51
52 addPlannerProgressProperty("best cost REAL", [this] { return getBestCost(); });
53 addPlannerProgressProperty("shared paths INTEGER", [this] { return getNumPathsShared(); });
54 addPlannerProgressProperty("shared states INTEGER", [this] { return getNumStatesShared(); });
55}
56
57ompl::geometric::CForest::~CForest() = default;
58
59void ompl::geometric::CForest::setNumThreads(unsigned int numThreads)
60{
61 numThreads_ = numThreads != 0u ? numThreads : std::max(std::thread::hardware_concurrency(), 2u);
62}
63
64void ompl::geometric::CForest::addPlannerInstanceInternal(const base::PlannerPtr &planner)
65{
66 if (!planner->getSpecs().canReportIntermediateSolutions)
67 OMPL_WARN("%s cannot report intermediate solutions, not added as CForest planner.", planner->getName().c_str());
68 else
69 {
70 planner->setProblemDefinition(pdef_);
71 if (planner->params().hasParam("focus_search"))
72 planner->params()["focus_search"] = focusSearch_;
73 else
74 OMPL_WARN("%s does not appear to support search focusing.", planner->getName().c_str());
75
76 planners_.push_back(planner);
77 }
78}
79
81{
82 Planner::getPlannerData(data);
83
84 for (std::size_t i = 0; i < planners_.size(); ++i)
85 {
87 planners_[i]->getPlannerData(pd);
88
89 for (unsigned int j = 0; j < pd.numVertices(); ++j)
90 {
92
93 v.setTag(i);
94 std::vector<unsigned int> edgeList;
95 unsigned int numEdges = pd.getIncomingEdges(j, edgeList);
96 for (unsigned int k = 0; k < numEdges; ++k)
97 {
98 base::Cost edgeWeight;
99 base::PlannerDataVertex &w = pd.getVertex(edgeList[k]);
100
101 w.setTag(i);
102 pd.getEdgeWeight(j, k, &edgeWeight);
103 data.addEdge(v, w, pd.getEdge(j, k), edgeWeight);
104 }
105 }
106
107 for (unsigned int j = 0; j < pd.numGoalVertices(); ++j)
109
110 for (unsigned int j = 0; j < pd.numStartVertices(); ++j)
112 }
113}
114
116{
117 Planner::clear();
118 for (auto &planner : planners_)
119 planner->clear();
120
121 bestCost_ = base::Cost(std::numeric_limits<double>::quiet_NaN());
122 numPathsShared_ = 0;
124
125 std::vector<base::StateSamplerPtr> samplers;
126 samplers.reserve(samplers_.size());
127 for (auto &sampler : samplers_)
128 if (sampler.use_count() > 1)
129 samplers.push_back(sampler);
130 samplers_.swap(samplers);
131}
132
134{
135 Planner::setup();
136 if (pdef_->hasOptimizationObjective())
137 opt_ = pdef_->getOptimizationObjective();
138 else
139 {
140 OMPL_INFORM("%s: No optimization objective specified. Defaulting to optimizing path length for the allowed "
141 "planning time.",
142 getName().c_str());
143 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
144 }
145
146 bestCost_ = opt_->infiniteCost();
147
148 if (planners_.empty())
149 {
150 OMPL_INFORM("%s: Number and type of instances not specified. Defaulting to %d instances of RRTstar.",
151 getName().c_str(), numThreads_);
153 }
154
155 for (auto &planner : planners_)
156 if (!planner->isSetup())
157 planner->setup();
158
159 // This call is needed to make sure the ParamSet is up to date after changes induced by the planner setup calls
160 // above, via the state space wrappers for CForest.
161 si_->setup();
162}
163
165{
167
168 time::point start = time::now();
169 std::vector<std::thread *> threads(planners_.size());
170 const base::ReportIntermediateSolutionFn prevSolutionCallback =
171 getProblemDefinition()->getIntermediateSolutionCallback();
172
173 if (prevSolutionCallback)
174 OMPL_WARN("Cannot use previously set intermediate solution callback with %s", getName().c_str());
175
176 pdef_->setIntermediateSolutionCallback(
177 [this](const base::Planner *planner, const std::vector<const base::State *> &states, const base::Cost cost)
178 { return newSolutionFound(planner, states, cost); });
179 bestCost_ = opt_->infiniteCost();
180
181 // run each planner in its own thread, with the same ptc.
182 for (std::size_t i = 0; i < threads.size(); ++i)
183 {
184 base::Planner *planner = planners_[i].get();
185 threads[i] = new std::thread([this, planner, &ptc] { return solve(planner, ptc); });
186 }
187
188 for (auto &thread : threads)
189 {
190 thread->join();
191 delete thread;
192 }
193
194 // restore callback
195 getProblemDefinition()->setIntermediateSolutionCallback(prevSolutionCallback);
196 OMPL_INFORM("Solution found in %f seconds", time::seconds(time::now() - start));
197 return {pdef_->hasSolution(), pdef_->hasApproximateSolution()};
198}
199
201{
202 return ompl::toString(bestCost_.value());
203}
204
206{
207 return std::to_string(numPathsShared_);
208}
209
211{
212 return std::to_string(numStatesShared_);
213}
214
215void ompl::geometric::CForest::newSolutionFound(const base::Planner *planner,
216 const std::vector<const base::State *> &states, const base::Cost cost)
217{
218 bool change = false;
219 std::vector<const base::State *> statesToShare;
220 newSolutionFoundMutex_.lock();
221 if (opt_->isCostBetterThan(cost, bestCost_))
222 {
223 ++numPathsShared_;
224 bestCost_ = cost;
225 change = true;
226
227 // Filtering the states to add only those not already added.
228 statesToShare.reserve(states.size());
229 for (auto state : states)
230 {
231 if (statesShared_.find(state) == statesShared_.end())
232 {
233 statesShared_.insert(state);
234 statesToShare.push_back(state);
235 ++numStatesShared_;
236 }
237 }
238 }
239 newSolutionFoundMutex_.unlock();
240
241 if (!change || statesToShare.empty())
242 return;
243
244 for (auto &i : samplers_)
245 {
246 auto *sampler = static_cast<base::CForestStateSampler *>(i.get());
247 const auto *space = static_cast<const base::CForestStateSpaceWrapper *>(sampler->getStateSpace());
248 const base::Planner *cfplanner = space->getPlanner();
249 if (cfplanner != planner)
250 sampler->setStatesToSample(statesToShare);
251 }
252}
253
255{
256 OMPL_DEBUG("Starting %s", planner->getName().c_str());
257 time::point start = time::now();
258 try
259 {
260 if (planner->solve(ptc))
261 {
262 double duration = time::seconds(time::now() - start);
263 OMPL_DEBUG("Solution found by %s in %lf seconds", planner->getName().c_str(), duration);
264 }
265 }
266 catch (ompl::Exception &e)
267 {
268 OMPL_ERROR("Exception thrown during CForest::solve: %s", e.what());
269 }
270}
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
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
virtual void setTag(int tag)
Set the integer tag associated with this vertex.
Definition PlannerData.h:75
virtual const State * getState() const
Retrieve the state associated with this vertex.
Definition PlannerData.h:80
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
bool getEdgeWeight(unsigned int v1, unsigned int v2, Cost *weight) const
Returns the weight of the edge between the given vertex indices. If there exists an edge between v1 a...
bool markStartState(const State *st)
Mark the given state as a start vertex. If the given state does not exist in a vertex,...
bool markGoalState(const State *st)
Mark the given state as a goal vertex. If the given state does not exist in a vertex,...
unsigned int getIncomingEdges(unsigned int v, std::vector< unsigned int > &edgeList) const
Returns a list of vertices with outgoing edges to the vertex with index v. The number of edges connec...
unsigned int numVertices() const
Retrieve the number of vertices in this structure.
unsigned int numStartVertices() const
Returns the number of start vertices.
const PlannerDataEdge & getEdge(unsigned int v1, unsigned int v2) const
Retrieve a reference to the edge object connecting vertices with indexes v1 and v2....
const PlannerDataVertex & getStartVertex(unsigned int i) const
Retrieve a reference to the ith start vertex object. If i is greater than the number of start vertice...
const PlannerDataVertex & getVertex(unsigned int index) const
Retrieve a reference to the vertex object with the given index. If this vertex does not exist,...
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
unsigned int numGoalVertices() const
Returns the number of goal vertices.
const PlannerDataVertex & getGoalVertex(unsigned int i) const
Retrieve a reference to the ith goal vertex object. If i is greater than the number of goal vertices,...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition Planner.h:216
const ProblemDefinitionPtr & getProblemDefinition() const
Get the problem definition the planner is trying to solve.
Definition Planner.cpp:71
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
const std::string & getName() const
Get the name of the planner.
Definition Planner.cpp:56
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
virtual void checkValidity()
Check to see if the planner is in a working state (setup has been called, a goal was set,...
Definition Planner.cpp:106
virtual PlannerStatus solve(const PlannerTerminationCondition &ptc)=0
Function that can solve the motion planning problem. This function can be called multiple times on th...
unsigned int numThreads_
Default number of threads to use when no planner instances are specified by the user.
Definition CForest.h:208
std::vector< base::StateSamplerPtr > samplers_
The set of sampler allocated by the planners.
Definition CForest.h:184
std::vector< base::PlannerPtr > planners_
The set of planners to be used.
Definition CForest.h:181
base::Cost bestCost_
Cost of the best path found so far among planners.
Definition CForest.h:190
base::OptimizationObjectivePtr opt_
Optimization objective taken into account when planning.
Definition CForest.h:178
std::string getBestCost() const
Get best cost among all the planners.
Definition CForest.cpp:200
void addPlannerInstances(std::size_t num=2)
Add specific planner instances. CFOREST sets the planner's parameter named focus_search (if present) ...
Definition CForest.h:103
void setNumThreads(unsigned int numThreads=0)
Set default number of threads to use when no planner instances are specified by the user.
Definition CForest.cpp:59
unsigned int numPathsShared_
Number of paths shared among threads.
Definition CForest.h:193
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition CForest.cpp:115
std::string getNumPathsShared() const
Get number of paths shared by the algorithm.
Definition CForest.cpp:205
std::string getNumStatesShared() const
Get number of states actually shared by the algorithm.
Definition CForest.cpp:210
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition CForest.cpp:164
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition CForest.cpp:80
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition CForest.cpp:133
unsigned int numStatesShared_
Number of states shared among threads.
Definition CForest.h:196
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition Console.h:70
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines shared by both planning under geometric cons...
std::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> ReportIntermediateSolutionFn
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signatu...
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
std::string toString(float val)
convert float to string using classic "C" locale semantics
Definition String.cpp:82
A class to store the exit status of Planner::solve().