Loading...
Searching...
No Matches
pRRT.h
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#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_pRRT_
38#define OMPL_GEOMETRIC_PLANNERS_RRT_pRRT_
39
40#include "ompl/geometric/planners/PlannerIncludes.h"
41#include "ompl/base/StateSamplerArray.h"
42#include "ompl/datastructures/NearestNeighbors.h"
43#include <thread>
44#include <mutex>
45
46namespace ompl
47{
48 namespace geometric
49 {
66
68 class pRRT : public base::Planner
69 {
70 public:
71 pRRT(const base::SpaceInformationPtr &si);
72
73 ~pRRT() override;
74
75 void getPlannerData(base::PlannerData &data) const override;
76
78
79 void clear() override;
80
90 void setGoalBias(double goalBias)
91 {
92 goalBias_ = goalBias;
93 }
94
96 double getGoalBias() const
97 {
98 return goalBias_;
99 }
100
106 void setRange(double distance)
107 {
108 maxDistance_ = distance;
109 }
110
112 double getRange() const
113 {
114 return maxDistance_;
115 }
116
118 void setThreadCount(unsigned int nthreads);
119
120 unsigned int getThreadCount() const
121 {
122 return threadCount_;
123 }
124
126 template <template <typename T> class NN>
128 {
129 if (nn_ && nn_->size() != 0)
130 OMPL_WARN("Calling setNearestNeighbors will clear all states.");
131 clear();
132 nn_ = std::make_shared<NN<Motion *>>();
133 setup();
134 }
135
136 void setup() override;
137
138 protected:
139 class Motion
140 {
141 public:
142 Motion() = default;
143
144 Motion(const base::SpaceInformationPtr &si) : state(si->allocState())
145 {
146 }
147
148 ~Motion() = default;
149
150 base::State *state{nullptr};
151 Motion *parent{nullptr};
152 };
153
155 {
156 Motion *solution;
157 Motion *approxsol;
158 double approxdif;
159 std::mutex lock;
160 };
161
162 void threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol);
163 void freeMemory();
164
165 double distanceFunction(const Motion *a, const Motion *b) const
166 {
167 return si_->distance(a->state, b->state);
168 }
169
171 std::shared_ptr<NearestNeighbors<Motion *>> nn_;
172 std::mutex nnLock_;
173
174 unsigned int threadCount_;
175
176 double goalBias_{.05};
177 double maxDistance_{0.};
178
181 };
182 }
183}
184
185#endif
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition Planner.h:216
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:410
Class to ease the creation of a set of samplers. This is especially useful for multi-threaded planner...
Definition of an abstract state.
Definition State.h:50
void setGoalBias(double goalBias)
Set the goal bias.
Definition pRRT.h:90
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:252
double getGoalBias() const
Get the goal bias the planner is using.
Definition pRRT.h:96
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition pRRT.h:180
double getRange() const
Get the range the planner is using.
Definition pRRT.h:112
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition pRRT.cpp:74
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 setRange(double distance)
Set the range the planner is supposed to use.
Definition pRRT.h:106
void setThreadCount(unsigned int nthreads)
Set the number of threads the planner should use. Default is 2.
Definition pRRT.cpp:272
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition pRRT.h:127
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:172
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains code that is specific to planning under geometric constraints.
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve()