Loading...
Searching...
No Matches
SST.h
1/*********************************************************************
2* Software License Agreement (BSD License)
3*
4* Copyright (c) 2015, Rutgers the State University of New Jersey, New Brunswick
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 Rutgers 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: Zakary Littlefield */
36
37#ifndef OMPL_CONTROL_PLANNERS_SST_SST_
38#define OMPL_CONTROL_PLANNERS_SST_SST_
39
40#include "ompl/control/planners/PlannerIncludes.h"
41#include "ompl/datastructures/NearestNeighbors.h"
42
43namespace ompl
44{
45 namespace control
46 {
59 class SST : public base::Planner
60 {
61 public:
63 SST(const SpaceInformationPtr &si);
64
65 ~SST() override;
66
67 void setup() override;
68
71
72 void getPlannerData(base::PlannerData &data) const override;
73
77 void clear() override;
78
86 void setGoalBias(double goalBias)
87 {
88 goalBias_ = goalBias;
89 }
90
92 double getGoalBias() const
93 {
94 return goalBias_;
95 }
96
105 void setSelectionRadius(double selectionRadius)
106 {
107 selectionRadius_ = selectionRadius;
108 }
109
111 double getSelectionRadius() const
112 {
113 return selectionRadius_;
114 }
115
126 void setPruningRadius(double pruningRadius)
127 {
128 pruningRadius_ = pruningRadius;
129 }
130
132 double getPruningRadius() const
133 {
134 return pruningRadius_;
135 }
136
138 template <template <typename T> class NN>
140 {
141 if (nn_ && nn_->size() != 0)
142 OMPL_WARN("Calling setNearestNeighbors will clear all states.");
143 clear();
144 nn_ = std::make_shared<NN<Motion *>>();
145 witnesses_ = std::make_shared<NN<Motion *>>();
146 setup();
147 }
148
149 protected:
154 class Motion
155 {
156 public:
157 Motion() = default;
158
161 : state_(si->allocState()), control_(si->allocControl())
162 {
163 }
164
165 virtual ~Motion() = default;
166
167 virtual base::State *getState() const
168 {
169 return state_;
170 }
171 virtual Motion *getParent() const
172 {
173 return parent_;
174 }
175
176 base::Cost accCost_{0};
177
180
182 Control *control_{nullptr};
183
185 unsigned int steps_{0};
186
188 Motion *parent_{nullptr};
189
191 unsigned numChildren_{0};
192
194 bool inactive_{false};
195 };
196
197 class Witness : public Motion
198 {
199 public:
200 Witness() = default;
201
202 Witness(const SpaceInformation *si) : Motion(si)
203 {
204 }
205 base::State *getState() const override
206 {
207 return rep_->state_;
208 }
209 Motion *getParent() const override
210 {
211 return rep_->parent_;
212 }
213
214 void linkRep(Motion *lRep)
215 {
216 rep_ = lRep;
217 }
218
220 Motion *rep_{nullptr};
221 };
222
224 Motion *selectNode(Motion *sample);
225
227 Witness *findClosestWitness(Motion *node);
228
230 void freeMemory();
231
233 double distanceFunction(const Motion *a, const Motion *b) const
234 {
235 return si_->distance(a->state_, b->state_);
236 }
237
239 base::StateSamplerPtr sampler_;
240
243
246
248 std::shared_ptr<NearestNeighbors<Motion *>> nn_;
249
251 std::shared_ptr<NearestNeighbors<Motion *>> witnesses_;
252
255 double goalBias_{0.05};
256
258 double selectionRadius_{0.2};
259
261 double pruningRadius_{0.1};
262
265
267 std::vector<base::State *> prevSolution_;
268 std::vector<Control *> prevSolutionControls_;
269 std::vector<unsigned> prevSolutionSteps_;
270
273
275 base::OptimizationObjectivePtr opt_;
276 };
277 }
278}
279
280#endif
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
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
A shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition State.h:50
A shared pointer wrapper for ompl::control::ControlSampler.
Definition of an abstract control.
Definition Control.h:48
Representation of a motion.
Definition SST.h:155
base::State * state_
The state contained by the motion.
Definition SST.h:179
unsigned numChildren_
Number of children.
Definition SST.h:191
Motion(const SpaceInformation *si)
Constructor that allocates memory for the state and the control.
Definition SST.h:160
Control * control_
The control contained by the motion.
Definition SST.h:182
unsigned int steps_
The number of steps_ the control is applied for.
Definition SST.h:185
Motion * parent_
The parent motion in the exploration tree.
Definition SST.h:188
bool inactive_
If inactive, this node is not considered for selection.
Definition SST.h:194
Motion * rep_
The node in the tree that is within the pruning radius.
Definition SST.h:220
ControlSamplerPtr controlSampler_
Control sampler.
Definition SST.h:242
void setGoalBias(double goalBias)
Definition SST.h:86
RNG rng_
The random number generator.
Definition SST.h:264
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 SST.cpp:413
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
Definition SST.h:105
base::StateSamplerPtr sampler_
State sampler.
Definition SST.h:239
SST(const SpaceInformationPtr &si)
Constructor.
Definition SST.cpp:46
double getGoalBias() const
Get the goal bias the planner is using.
Definition SST.h:92
void freeMemory()
Free the memory allocated by this planner.
Definition SST.cpp:118
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition SST.cpp:65
double selectionRadius_
The radius for determining the node selected for extension.
Definition SST.h:258
double pruningRadius_
The radius for determining the size of the pruning region.
Definition SST.h:261
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition SST.cpp:210
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition SST.h:272
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)
Definition SST.h:255
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition SST.h:245
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition SST.h:233
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
Definition SST.cpp:157
double getSelectionRadius() const
Get the selection radius the planner is using.
Definition SST.h:111
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition SST.h:248
base::OptimizationObjectivePtr opt_
The optimization objective.
Definition SST.h:275
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
A nearest-neighbors datastructure containing the tree of witness motions.
Definition SST.h:251
double getPruningRadius() const
Get the pruning radius the planner is using.
Definition SST.h:132
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition SST.h:139
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition SST.h:126
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition SST.h:267
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition SST.cpp:104
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
Definition SST.cpp:186
Space information containing necessary information for planning with controls. setup() needs to be ca...
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition Control.h:45
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve()