37 #ifndef OMPL_GEOMETRIC_PLANNERS_SST_SST_
38 #define OMPL_GEOMETRIC_PLANNERS_SST_SST_
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
59 class SST :
public base::Planner
63 SST(
const base::SpaceInformationPtr &si);
67 void setup()
override;
70 base::PlannerStatus
solve(
const base::PlannerTerminationCondition &ptc)
override;
77 void clear()
override;
154 template <
template <
typename T>
class NN>
157 if (
nn_ &&
nn_->size() != 0)
158 OMPL_WARN(
"Calling setNearestNeighbors will clear all states.");
160 nn_ = std::make_shared<NN<Motion *>>();
161 witnesses_ = std::make_shared<NN<Motion *>>();
176 Motion(
const base::SpaceInformationPtr &si)
177 :
state_(si->allocState())
181 virtual ~Motion() =
default;
187 virtual Motion *getParent()
const
206 class Witness :
public Motion
211 Witness(
const base::SpaceInformationPtr &si) : Motion(si)
218 Motion *getParent()
const override
229 Motion *
rep_{
nullptr};
247 return si_->distance(a->state_, b->state_);
254 std::shared_ptr<NearestNeighbors<Motion *>>
nn_;
257 std::shared_ptr<NearestNeighbors<Motion *>>
witnesses_;
282 base::OptimizationObjectivePtr
opt_;
base::OptimizationObjectivePtr opt_
The optimization objective.
base::State * monteCarloProp(Motion *m)
Randomly propagate a new edge.
bool inactive_
If inactive, this node is not considered for selection.
unsigned numChildren_
Number of children.
double getPruningRadius() const
Get the pruning radius the planner is using.
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition of an abstract state.
Motion * parent_
The parent motion in the exploration tree.
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
A nearest-neighbors datastructure containing the tree of witness motions.
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
double maxDistance_
The maximum length of a motion to be added to a tree.
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
base::StateSamplerPtr sampler_
State sampler.
void freeMemory()
Free the memory allocated by this planner.
SST(const base::SpaceInformationPtr &si)
Constructor.
double getGoalBias() const
Get the goal bias the planner is using.
base::Cost prevSolutionCost_
The best solution cost we found so far.
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
double selectionRadius_
The radius for determining the node selected for extension.
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
std::vector< base::State * > prevSolution_
The best solution we found so far.
double getSelectionRadius() const
Get the selection radius the planner is using.
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
base::State * state_
The state contained by the motion.
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
double getRange() const
Get the range the planner is using.
void setGoalBias(double goalBias)
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
double pruningRadius_
The radius for determining the size of the pruning region.
SpaceInformationPtr si_
The space information for which planning is done.
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Motion * rep_
The node in the tree that is within the pruning radius.
void setRange(double distance)
Set the range the planner is supposed to use.
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
RNG rng_
The random number generator.
Representation of a motion.
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Main namespace. Contains everything in this library.