Program Listing for File RRTXstatic.h
↰ Return to documentation for file (src/ompl/geometric/planners/rrt/RRTXstatic.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2016, Georgia Institute of Technology
* 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.
*********************************************************************/
/* Author: Florian Hauer */
#ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRTXSTATIC_
#define OMPL_GEOMETRIC_PLANNERS_RRT_RRTXSTATIC_
#include <ompl/datastructures/BinaryHeap.h>
#include "ompl/base/OptimizationObjective.h"
#include "ompl/datastructures/NearestNeighbors.h"
#include "ompl/geometric/planners/PlannerIncludes.h"
#include <deque>
#include <limits>
#include <list>
#include <queue>
#include <utility>
#include <vector>
namespace ompl
{
namespace geometric
{
class RRTXstatic : public base::Planner
{
public:
RRTXstatic(const base::SpaceInformationPtr &si);
~RRTXstatic() 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 setInformedSampling(bool informedSampling);
bool getInformedSampling() const
{
return useInformedSampling_;
}
void setSampleRejection(bool reject);
bool getSampleRejection() const
{
return useRejectionSampling_;
}
void setNumSamplingAttempts(unsigned int numAttempts)
{
numSampleAttempts_ = numAttempts;
}
unsigned int getNumSamplingAttempts() const
{
return numSampleAttempts_;
}
virtual void setEpsilon(double epsilon)
{
epsilonCost_ = base::Cost(epsilon);
}
double getEpsilon() const
{
return epsilonCost_.value();
}
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 setKNearest(bool useKNearest)
{
useKNearest_ = useKNearest;
}
bool getKNearest() const
{
return useKNearest_;
}
void setUpdateChildren(bool val)
{
updateChildren_ = val;
}
bool getUpdateChildren() const
{
return updateChildren_;
}
void setVariant(const int variant)
{
if (variant < 0 || variant > 3)
throw Exception("Variant must be 0 (original RRT#) or in [1, 3]");
variant_ = variant;
}
int getVariant() const
{
return variant_;
}
void setAlpha(const double a)
{
alpha_ = a;
}
double getAlpha() const
{
return alpha_;
}
unsigned int numIterations() const
{
return iterations_;
}
ompl::base::Cost bestCost() const
{
return bestCost_;
}
protected:
class Motion;
struct MotionCompare
{
MotionCompare(base::OptimizationObjectivePtr opt, base::ProblemDefinitionPtr pdef)
: opt_(std::move(opt)), pdef_(std::move(pdef))
{
}
inline base::Cost costPlusHeuristic(const Motion *m) const
{
return opt_->combineCosts(m->cost, opt_->costToGo(m->state, pdef_->getGoal().get()));
}
inline base::Cost alphaCostPlusHeuristic(const Motion *m, double alpha) const
{
return opt_->combineCosts(base::Cost(alpha * m->cost.value()),
opt_->costToGo(m->state, pdef_->getGoal().get()));
}
inline bool operator()(const Motion *m1, const Motion *m2) const
{
// we use a max heap, to do a min heap so the operator < returns > in order to make it a min heap
return !opt_->isCostBetterThan(costPlusHeuristic(m1), costPlusHeuristic(m2));
}
base::OptimizationObjectivePtr opt_;
base::ProblemDefinitionPtr pdef_;
};
class Motion
{
public:
Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(nullptr), handle(nullptr)
{
}
~Motion() = default;
base::State *state;
Motion *parent;
base::Cost cost;
std::vector<Motion *> children;
std::vector<std::pair<Motion *, bool>> nbh;
BinaryHeap<Motion *, MotionCompare>::Element *handle;
};
void allocSampler();
bool sampleUniform(base::State *statePtr);
void freeMemory();
double distanceFunction(const Motion *a, const Motion *b) const
{
return si_->distance(a->state, b->state);
}
void updateQueue(Motion *x);
void removeFromParent(Motion *m);
void getNeighbors(Motion *motion) const;
void calculateRewiringLowerBounds();
void calculateRRG();
bool includeVertex(const Motion *x) const;
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.};
base::OptimizationObjectivePtr opt_;
Motion *lastGoalMotion_{nullptr};
std::vector<Motion *> goalMotions_;
base::Cost bestCost_{std::numeric_limits<double>::quiet_NaN()};
unsigned int iterations_{0u};
MotionCompare mc_;
BinaryHeap<Motion *, MotionCompare> q_;
base::Cost epsilonCost_{0.};
bool updateChildren_{true};
double rrg_r_;
unsigned int rrg_k_;
int variant_{0};
double alpha_{1.};
bool useInformedSampling_{false};
bool useRejectionSampling_{false};
unsigned int numSampleAttempts_{100u};
// Planner progress property functions
std::string numIterationsProperty() const
{
return std::to_string(numIterations());
}
std::string bestCostProperty() const
{
return std::to_string(bestCost().value());
}
std::string numMotionsProperty() const
{
return std::to_string(nn_->size());
}
};
}
}
#endif