Loading...
Searching...
No Matches
pRRT.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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/geometric/planners/rrt/pRRT.h"
38#include "ompl/base/goals/GoalSampleableRegion.h"
39#include "ompl/tools/config/SelfConfig.h"
40#include <limits>
41
42ompl::geometric::pRRT::pRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "pRRT"), samplerArray_(si)
43{
44 specs_.approximateSolutions = true;
45 specs_.multithreaded = true;
46 specs_.directed = true;
47
48 setThreadCount(2);
49
50 Planner::declareParam<double>("range", this, &pRRT::setRange, &pRRT::getRange, "0.:1.:10000.");
51 Planner::declareParam<double>("goal_bias", this, &pRRT::setGoalBias, &pRRT::getGoalBias, "0.:.05:1.");
52 Planner::declareParam<unsigned int>("thread_count", this, &pRRT::setThreadCount, &pRRT::getThreadCount, "1:64");
53}
54
55ompl::geometric::pRRT::~pRRT()
56{
57 freeMemory();
58}
59
61{
62 Planner::setup();
64 sc.configurePlannerRange(maxDistance_);
65
66 if (!nn_)
68 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
69}
70
72{
73 Planner::clear();
74 samplerArray_.clear();
75 freeMemory();
76 if (nn_)
77 nn_->clear();
78 lastGoalMotion_ = nullptr;
79}
80
81void ompl::geometric::pRRT::freeMemory()
82{
83 if (nn_)
84 {
85 std::vector<Motion *> motions;
86 nn_->list(motions);
87 for (auto &motion : motions)
88 {
89 if (motion->state)
90 si_->freeState(motion->state);
91 delete motion;
92 }
93 }
94}
95
96void ompl::geometric::pRRT::threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc,
97 SolutionInfo *sol)
98{
99 base::Goal *goal = pdef_->getGoal().get();
100 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
101 RNG rng;
102
103 auto *rmotion = new Motion(si_);
104 base::State *rstate = rmotion->state;
105 base::State *xstate = si_->allocState();
106
107 while (sol->solution == nullptr && ptc == false)
108 {
109 /* sample random state (with goal biasing) */
110 if (goal_s && rng.uniform01() < goalBias_ && goal_s->canSample())
111 goal_s->sampleGoal(rstate);
112 else
113 samplerArray_[tid]->sampleUniform(rstate);
114
115 /* find closest state in the tree */
116 nnLock_.lock();
117 Motion *nmotion = nn_->nearest(rmotion);
118 nnLock_.unlock();
119 base::State *dstate = rstate;
120
121 /* find state to add */
122 double d = si_->distance(nmotion->state, rstate);
123 if (d > maxDistance_)
124 {
125 si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
126 dstate = xstate;
127 }
128
129 if (si_->checkMotion(nmotion->state, dstate))
130 {
131 /* create a motion */
132 auto *motion = new Motion(si_);
133 si_->copyState(motion->state, dstate);
134 motion->parent = nmotion;
135
136 nnLock_.lock();
137 nn_->add(motion);
138 nnLock_.unlock();
139
140 double dist = 0.0;
141 bool solved = goal->isSatisfied(motion->state, &dist);
142 if (solved)
143 {
144 sol->lock.lock();
145 sol->approxdif = dist;
146 sol->solution = motion;
147 sol->lock.unlock();
148 break;
149 }
150 if (dist < sol->approxdif)
151 {
152 sol->lock.lock();
153 if (dist < sol->approxdif)
154 {
155 sol->approxdif = dist;
156 sol->approxsol = motion;
157 }
158 sol->lock.unlock();
159 }
160 }
161 }
162
163 si_->freeState(xstate);
164 if (rmotion->state)
165 si_->freeState(rmotion->state);
166 delete rmotion;
167}
168
170{
172
173 auto *goal = dynamic_cast<base::GoalRegion *>(pdef_->getGoal().get());
174
175 if (goal == nullptr)
176 {
177 OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
179 }
180
181 samplerArray_.resize(threadCount_);
182
183 while (const base::State *st = pis_.nextStart())
184 {
185 auto *motion = new Motion(si_);
186 si_->copyState(motion->state, st);
187 nn_->add(motion);
188 }
189
190 if (nn_->size() == 0)
191 {
192 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
194 }
195
196 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
197
198 SolutionInfo sol;
199 sol.solution = nullptr;
200 sol.approxsol = nullptr;
201 sol.approxdif = std::numeric_limits<double>::infinity();
202
203 std::vector<std::thread *> th(threadCount_);
204 for (unsigned int i = 0; i < threadCount_; ++i)
205 th[i] = new std::thread([this, i, &ptc, &sol] { return threadSolve(i, ptc, &sol); });
206 for (unsigned int i = 0; i < threadCount_; ++i)
207 {
208 th[i]->join();
209 delete th[i];
210 }
211
212 bool solved = false;
213 bool approximate = false;
214 if (sol.solution == nullptr)
215 {
216 sol.solution = sol.approxsol;
217 approximate = true;
218 }
219
220 if (sol.solution != nullptr)
221 {
222 lastGoalMotion_ = sol.solution;
223
224 /* construct the solution path */
225 std::vector<Motion *> mpath;
226 while (sol.solution != nullptr)
227 {
228 mpath.push_back(sol.solution);
229 sol.solution = sol.solution->parent;
230 }
231
232 /* set the solution path */
233 auto path(std::make_shared<PathGeometric>(si_));
234 for (int i = mpath.size() - 1; i >= 0; --i)
235 path->append(mpath[i]->state);
236
237 pdef_->addSolutionPath(path, approximate, sol.approxdif, getName());
238 solved = true;
239 }
240
241 OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
242
243 return {solved, approximate};
244}
245
247{
248 Planner::getPlannerData(data);
249
250 std::vector<Motion *> motions;
251 if (nn_)
252 nn_->list(motions);
253
254 if (lastGoalMotion_)
256
257 for (auto &motion : motions)
258 {
259 if (motion->parent == nullptr)
260 data.addStartVertex(base::PlannerDataVertex(motion->state));
261 else
262 data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
263 }
264}
265
266void ompl::geometric::pRRT::setThreadCount(unsigned int nthreads)
267{
268 assert(nthreads > 0);
269 threadCount_ = nthreads;
270}
Definition of a goal region.
Definition GoalRegion.h:48
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
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...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerInputStates pis_
Utility class to extract valid input states.
Definition Planner.h:407
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
Definition of an abstract state.
Definition State.h:50
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 pRRT.cpp:246
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition pRRT.h:180
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition pRRT.cpp:71
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition pRRT.cpp:60
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Definition pRRT.cpp:266
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 pRRT.cpp:169
This class contains methods that automatically configure various parameters for motion planning....
Definition SelfConfig.h:59
static NearestNeighbors< _T > * getDefaultNearestNeighbors(const base::Planner *planner)
Select a default nearest neighbor datastructure for the given space.
Definition SelfConfig.h:105
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
#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
This namespace contains sampling based planning routines shared by both planning under geometric cons...
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.