Program Listing for File RRTstar.h
↰ Return to documentation for file (src/ompl/geometric/planners/rrt/RRTstar.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Rice University
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Rice University nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Authors: Alejandro Perez, Sertac Karaman, Ryan Luna, Luis G. Torres, Ioan Sucan, Javier V Gomez, Jonathan Gammell */
#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRTSTAR_
#define OMPL_GEOMETRIC_PLANNERS_RRT_RRTSTAR_
#include "ompl/geometric/planners/PlannerIncludes.h"
#include "ompl/base/OptimizationObjective.h"
#include "ompl/datastructures/NearestNeighbors.h"
#include <limits>
#include <vector>
#include <queue>
#include <deque>
#include <utility>
#include <list>
namespace ompl
{
namespace geometric
{
class RRTstar : public base::Planner
{
public:
RRTstar(const base::SpaceInformationPtr &si);
~RRTstar() override;
void getPlannerData(base::PlannerData &data) const override;
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
void clear() override;
void setup() override;
void setGoalBias(double goalBias)
{
goalBias_ = goalBias;
}
double getGoalBias() const
{
return goalBias_;
}
void setRange(double distance)
{
maxDistance_ = distance;
}
double getRange() const
{
return maxDistance_;
}
void setRewireFactor(double rewireFactor)
{
rewireFactor_ = rewireFactor;
calculateRewiringLowerBounds();
}
double getRewireFactor() const
{
return rewireFactor_;
}
template <template <typename T> class NN>
void setNearestNeighbors()
{
if (nn_ && nn_->size() != 0)
OMPL_WARN("Calling setNearestNeighbors will clear all states.");
clear();
nn_ = std::make_shared<NN<Motion *>>();
setup();
}
void setDelayCC(bool delayCC)
{
delayCC_ = delayCC;
}
bool getDelayCC() const
{
return delayCC_;
}
void setTreePruning(bool prune);
bool getTreePruning() const
{
return useTreePruning_;
}
void setPruneThreshold(const double pp)
{
pruneThreshold_ = pp;
}
double getPruneThreshold() const
{
return pruneThreshold_;
}
void setPrunedMeasure(bool informedMeasure);
bool getPrunedMeasure() const
{
return usePrunedMeasure_;
}
void setInformedSampling(bool informedSampling);
bool getInformedSampling() const
{
return useInformedSampling_;
}
void setSampleRejection(bool reject);
bool getSampleRejection() const
{
return useRejectionSampling_;
}
void setNewStateRejection(const bool reject)
{
useNewStateRejection_ = reject;
}
bool getNewStateRejection() const
{
return useNewStateRejection_;
}
void setAdmissibleCostToCome(const bool admissible)
{
useAdmissibleCostToCome_ = admissible;
}
bool getAdmissibleCostToCome() const
{
return useAdmissibleCostToCome_;
}
void setOrderedSampling(bool orderSamples);
bool getOrderedSampling() const
{
return useOrderedSampling_;
}
void setBatchSize(unsigned int batchSize)
{
batchSize_ = batchSize;
}
unsigned int getBatchSize() const
{
return batchSize_;
}
void setFocusSearch(const bool focus)
{
setInformedSampling(focus);
setTreePruning(focus);
setPrunedMeasure(focus);
setNewStateRejection(focus);
}
bool getFocusSearch() const
{
return getInformedSampling() && getPrunedMeasure() && getTreePruning() && getNewStateRejection();
}
void setKNearest(bool useKNearest)
{
useKNearest_ = useKNearest;
}
bool getKNearest() const
{
return useKNearest_;
}
void setNumSamplingAttempts(unsigned int numAttempts)
{
numSampleAttempts_ = numAttempts;
}
unsigned int getNumSamplingAttempts() const
{
return numSampleAttempts_;
}
unsigned int numIterations() const
{
return iterations_;
}
ompl::base::Cost bestCost() const
{
return bestCost_;
}
protected:
class Motion
{
public:
Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(nullptr), inGoal(false)
{
}
~Motion() = default;
base::State *state;
Motion *parent;
bool inGoal;
base::Cost cost;
base::Cost incCost;
std::vector<Motion *> children;
};
void allocSampler();
bool sampleUniform(base::State *statePtr);
void freeMemory();
// For sorting a list of costs and getting only their sorted indices
struct CostIndexCompare
{
CostIndexCompare(const std::vector<base::Cost> &costs, const base::OptimizationObjective &opt)
: costs_(costs), opt_(opt)
{
}
bool operator()(unsigned i, unsigned j)
{
return opt_.isCostBetterThan(costs_[i], costs_[j]);
}
const std::vector<base::Cost> &costs_;
const base::OptimizationObjective &opt_;
};
double distanceFunction(const Motion *a, const Motion *b) const
{
return si_->distance(a->state, b->state);
}
void getNeighbors(Motion *motion, std::vector<Motion *> &nbh) const;
void removeFromParent(Motion *m);
void updateChildCosts(Motion *m);
int pruneTree(const base::Cost &pruneTreeCost);
base::Cost solutionHeuristic(const Motion *motion) const;
void addChildrenToList(std::queue<Motion *, std::deque<Motion *>> *motionList, Motion *motion);
bool keepCondition(const Motion *motion, const base::Cost &threshold) const;
void calculateRewiringLowerBounds();
base::StateSamplerPtr sampler_;
base::InformedSamplerPtr infSampler_;
std::shared_ptr<NearestNeighbors<Motion *>> nn_;
double goalBias_{.05};
double maxDistance_{0.};
RNG rng_;
bool useKNearest_{true};
double rewireFactor_{1.1};
double k_rrt_{0u};
double r_rrt_{0.};
bool delayCC_{true};
base::OptimizationObjectivePtr opt_;
Motion *bestGoalMotion_{nullptr};
std::vector<Motion *> goalMotions_;
bool useTreePruning_{false};
double pruneThreshold_{.05};
bool usePrunedMeasure_{false};
bool useInformedSampling_{false};
bool useRejectionSampling_{false};
bool useNewStateRejection_{false};
bool useAdmissibleCostToCome_{true};
unsigned int numSampleAttempts_{100u};
bool useOrderedSampling_{false};
unsigned int batchSize_{1u};
std::vector<Motion *> startMotions_;
base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
base::Cost prunedCost_{std::numeric_limits<double>::quiet_NaN()};
double prunedMeasure_{0.};
unsigned int iterations_{0u};
// Planner progress property functions
std::string numIterationsProperty() const
{
return std::to_string(numIterations());
}
std::string bestCostProperty() const
{
return std::to_string(bestCost().value());
}
};
}
}
#endif