Program Listing for File BFMT.h
↰ Return to documentation for file (src/ompl/geometric/planners/fmt/BFMT.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, Autonomous Systems Laboratory, Stanford 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 Stanford 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: Joseph Starek (Stanford) */
/* Co-developers: Javier V Gomez (UC3M)*/
/* Algorithm design: Joseph Starek (Stanford), Ed Schmerling (Stanford), Lucas Janson (Stanford) and Marco Pavone
* (Stanford) */
/* Acknowledgements for insightful comments: Ashley Clark (Stanford) */
#ifndef OMPL_GEOMETRIC_PLANNERS_BIDIRECTIONALFMT_H
#define OMPL_GEOMETRIC_PLANNERS_BIDIRECTIONALFMT_H
#include <ompl/geometric/planners/PlannerIncludes.h>
#include <ompl/base/goals/GoalSampleableRegion.h>
#include <ompl/datastructures/NearestNeighbors.h>
#include <ompl/datastructures/BinaryHeap.h>
#include <ompl/base/OptimizationObjective.h>
#include <map>
#include <utility>
namespace ompl
{
namespace geometric
{
class BFMT : public ompl::base::Planner
{
public:
enum TreeType
{
FWD = 0,
REV = 1
};
enum ExploreType
{
SWAP_EVERY_TIME = 0,
CHOOSE_SMALLEST_Z = 1
};
enum TerminateType
{
FEASIBILITY = 0,
OPTIMALITY = 1
};
BFMT(const base::SpaceInformationPtr &si);
~BFMT() override;
void setup() override;
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
void clear() override;
void getPlannerData(base::PlannerData &data) const override;
void setNumSamples(const unsigned int numSamples)
{
numSamples_ = numSamples;
}
unsigned int getNumSamples() const
{
return numSamples_;
}
void setNearestK(bool nearestK)
{
nearestK_ = nearestK;
}
bool getNearestK() const
{
return nearestK_;
}
void setRadiusMultiplier(const double radiusMultiplier)
{
if (radiusMultiplier <= 0.0)
throw Exception("Radius multiplier must be greater than zero");
radiusMultiplier_ = radiusMultiplier;
}
double getRadiusMultiplier() const
{
return radiusMultiplier_;
}
void setFreeSpaceVolume(const double freeSpaceVolume)
{
if (freeSpaceVolume < 0.0)
throw Exception("Free space volume should be greater than zero");
freeSpaceVolume_ = freeSpaceVolume;
}
double getFreeSpaceVolume() const
{
return freeSpaceVolume_;
}
void setCacheCC(bool ccc)
{
cacheCC_ = ccc;
}
bool getCacheCC() const
{
return cacheCC_;
}
void setHeuristics(bool h)
{
heuristics_ = h;
}
bool getHeuristics() const
{
return heuristics_;
}
void setExtendedFMT(bool e)
{
extendedFMT_ = e;
}
bool getExtendedFMT() const
{
return extendedFMT_;
}
void setExploration(bool balanced)
{
exploration_ = SWAP_EVERY_TIME;
if (balanced)
{
exploration_ = CHOOSE_SMALLEST_Z;
}
}
bool getExploration() const
{
return (exploration_ == CHOOSE_SMALLEST_Z);
}
void setTermination(bool optimality)
{
termination_ = FEASIBILITY;
if (optimality)
{
termination_ = OPTIMALITY;
}
}
bool getTermination() const
{
return (termination_ == OPTIMALITY);
}
void setPrecomputeNN(bool p)
{
precomputeNN_ = p;
}
bool setPrecomputeNN() const
{
return precomputeNN_;
}
class BiDirMotion
{
public:
enum SetType
{
SET_CLOSED,
SET_OPEN,
SET_UNVISITED
};
BiDirMotion(TreeType *tree) : state_(nullptr), tree_(tree)
{
parent_[FWD] = nullptr;
parent_[REV] = nullptr;
cost_[FWD] = base::Cost(0.0);
cost_[REV] = base::Cost(0.0);
hcost_[FWD] = base::Cost(0.0);
hcost_[REV] = base::Cost(0.0);
currentSet_[FWD] = SET_UNVISITED;
currentSet_[REV] = SET_UNVISITED;
}
BiDirMotion(const base::SpaceInformationPtr &si, TreeType *tree) : state_(si->allocState()), tree_(tree)
{
parent_[FWD] = nullptr;
parent_[REV] = nullptr;
cost_[FWD] = base::Cost(0.0);
cost_[REV] = base::Cost(0.0);
hcost_[FWD] = base::Cost(0.0);
hcost_[REV] = base::Cost(0.0);
currentSet_[FWD] = SET_UNVISITED;
currentSet_[REV] = SET_UNVISITED;
}
using BiDirMotionPtrs = std::vector<BiDirMotion *>;
base::State *state_;
BiDirMotion *parent_[2];
BiDirMotionPtrs children_[2];
SetType currentSet_[2];
TreeType *tree_;
base::Cost cost_[2];
base::Cost hcost_[2];
std::set<BiDirMotion *> collChecksDone_;
inline base::Cost getCost() const
{
return this->cost_[*tree_];
}
inline base::Cost getOtherCost() const
{
return this->cost_[(*tree_ + 1) % 2];
}
inline void setCost(base::Cost cost)
{
this->cost_[*tree_] = cost;
}
inline void setParent(BiDirMotion *parent)
{
this->parent_[*tree_] = parent;
}
inline BiDirMotion *getParent() const
{
return this->parent_[*tree_];
}
inline void setChildren(BiDirMotionPtrs children)
{
this->children_[*tree_] = std::move(children);
}
inline BiDirMotionPtrs getChildren() const
{
return this->children_[*tree_];
}
inline void setCurrentSet(SetType set)
{
this->currentSet_[*tree_] = set;
}
inline SetType getCurrentSet() const
{
return this->currentSet_[*tree_];
}
inline SetType getOtherSet() const
{
return this->currentSet_[(*tree_ + 1) % 2];
}
inline void setTreeType(TreeType *treePtr)
{
this->tree_ = treePtr;
}
inline TreeType getTreeType() const
{
return *tree_;
}
void setState(base::State *state)
{
state_ = state;
}
base::State *getState() const
{
return state_;
}
bool alreadyCC(BiDirMotion *m)
{
return !(collChecksDone_.find(m) == collChecksDone_.end());
}
void addCC(BiDirMotion *m)
{
collChecksDone_.insert(m);
}
void setHeuristicCost(const base::Cost h)
{
hcost_[*tree_] = h;
}
base::Cost getHeuristicCost() const
{
return hcost_[*tree_];
}
};
using BiDirMotionPtrs = std::vector<BiDirMotion *>;
protected:
struct BiDirMotionCompare
{
bool operator()(const BiDirMotion *p1, const BiDirMotion *p2) const
{
if (heuristics_)
return (opt_->combineCosts(p1->getCost(), p1->getHeuristicCost()).value() <
opt_->combineCosts(p2->getCost(), p2->getHeuristicCost()).value());
return (p1->getCost().value() < p2->getCost().value());
}
base::OptimizationObjective *opt_;
bool heuristics_;
};
using BiDirMotionBinHeap = ompl::BinaryHeap<BiDirMotion *, BiDirMotionCompare>;
void swapTrees();
void useFwdTree()
{
tree_ = FWD;
}
void useRevTree()
{
tree_ = REV;
}
double distanceFunction(const BiDirMotion *a, const BiDirMotion *b) const
{
return opt_->motionCost(a->getState(), b->getState()).value();
}
double calculateUnitBallVolume(unsigned int dimension) const;
double calculateRadius(unsigned int dimension, unsigned int n) const;
void freeMemory();
void saveNeighborhood(BiDirMotion *m);
void sampleFree(const std::shared_ptr<NearestNeighbors<BiDirMotion *>> &nn,
const base::PlannerTerminationCondition &ptc);
void initializeProblem(base::GoalSampleableRegion *&goal_s);
void expandTreeFromNode(BiDirMotion *&z, BiDirMotion *&connection_point);
bool plan(BiDirMotion *x_init, BiDirMotion *x_goal, BiDirMotion *&connection_point,
const base::PlannerTerminationCondition &ptc);
bool termination(BiDirMotion *&z, BiDirMotion *&connection_point,
const base::PlannerTerminationCondition &ptc);
void chooseTreeAndExpansionNode(BiDirMotion *&z);
void tracePath(BiDirMotion *z, BiDirMotionPtrs &path);
void updateNeighborhood(BiDirMotion *m, std::vector<BiDirMotion *> nbh);
void insertNewSampleInOpen(const base::PlannerTerminationCondition &ptc);
unsigned int numSamples_{1000u};
double radiusMultiplier_{1.};
double freeSpaceVolume_;
unsigned int collisionChecks_{0u};
bool nearestK_{true};
double NNr_{0.};
unsigned int NNk_{0};
TreeType tree_{FWD};
ExploreType exploration_{SWAP_EVERY_TIME};
TerminateType termination_{OPTIMALITY};
bool precomputeNN_{false};
std::shared_ptr<NearestNeighbors<BiDirMotion *>> nn_;
std::map<BiDirMotion *, BiDirMotionPtrs> neighborhoods_;
BiDirMotionBinHeap Open_[2];
std::map<BiDirMotion *, BiDirMotionBinHeap::Element *> Open_elements[2];
base::StateSamplerPtr sampler_;
base::OptimizationObjectivePtr opt_;
bool heuristics_{true};
base::State *heurGoalState_[2];
bool cacheCC_{true};
bool extendedFMT_{true};
// 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 (costs_[i].value() < costs_[j].value());
}
const std::vector<base::Cost> &costs_;
const base::OptimizationObjective &opt_;
};
};
} // End "geometric" namespace
} // End "ompl" namespace
#endif /* OMPL_GEOMETRIC_PLANNERS_BIDIRECTIONALFMT_H */