Template Class BundleSpaceSequence

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

template<class T>
class BundleSpaceSequence : public ompl::multilevel::PlannerMultiLevel

A planner for a sequence of BundleSpaces.

Example usage with QRRT ompl::base::PlannerPtr planner = std::make_shared<BundleSpaceSequence<ompl::multilevel::QRRT> >(si_vec);

whereby si_vec is of type std::vector<ompl::base::SpaceInformationPtr>

Template Parameters:

T – Planner function used to grow each space

Public Functions

BundleSpaceSequence(ompl::base::SpaceInformationPtr si, std::string type = "BundleSpacePlannerNonMultilevel")

Non-multilevel Mode: Calling with a single ompl::base::SpaceInformationPtr will revert to standard planning without invoking any projection operators.

BundleSpaceSequence(std::vector<ompl::base::SpaceInformationPtr> &siVec, std::string type = "BundleSpacePlanner")

Basic Mode: Specify vector of ompl::base::SpaceInformationPtr and let the algorithm figure out the projections itself.

BundleSpaceSequence(std::vector<ompl::base::SpaceInformationPtr> &siVec, std::vector<ompl::multilevel::ProjectionPtr> &projVec, std::string type = "BundleSpacePlannerCustomProjection")

Advanced Mode: Specify not only the vector of ompl::base::SpaceInformationPtr, but also how we should project from each bundle space to each base space.

virtual ~BundleSpaceSequence()
void declareBundleSpaces(bool guessProjection = true)
virtual void getPlannerData(ompl::base::PlannerData &data) const override

Return annotated vertices (with information about BundleSpace level)

virtual ompl::base::PlannerStatus solve(const ompl::base::PlannerTerminationCondition &ptc) override

Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.

virtual void setup() override

Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.

virtual void clear() override

Clear multilevel planner by clearing all levels.

virtual void setProblemDefinition(const ompl::base::ProblemDefinitionPtr &pdef) override

Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery().

void setStopLevel(unsigned int level_)
void setFindSectionStrategy(FindSectionType type)

Set strategy to use to solve the find section problem.

Protected Types

typedef std::priority_queue<BundleSpace*, std::vector<BundleSpace*>, CmpBundleSpacePtrs> BundleSpacePriorityQueue

Priority queue of BundleSpaces which keeps track of how often every graph on each space has been expanded.

Protected Functions

ompl::base::State *getTotalState(int baseLevel, const base::State *baseState) const

Starting from a baseState on baseLevel, we lift it iteratively upwards into the total space of the sequence. For each lift, we choose an identity fiber element using the allocIdentityState method in ompl::multilevel::BundleSpace.

Protected Attributes

std::vector<T*> bundleSpaces_

Sequence of BundleSpaces.

bool foundKLevelSolution_ = {false}

Indicator if a solution has been found on the current BundleSpaces.

unsigned int currentBundleSpaceLevel_ = {0}

Current level on which we have not yet found a path.

unsigned int stopAtLevel_

Sometimes we only want to plan until a certain BundleSpace level (for debugging for example). This variable sets the stopping level.

BundleSpacePriorityQueue priorityQueue_
struct CmpBundleSpacePtrs

Compare function for priority queue.

Public Functions

inline bool operator()(const BundleSpace *lhs, const BundleSpace *rhs) const