Class XXL
Defined in File XXL.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class XXL : public ompl::base::Planner
XXL is a probabilistically complete sampling-based algorithm designed to plan the motions of high-dimensional mobile manipulators and related platforms. Using a novel sampling and connection strategy that guides a set of points mapped on the robot through the workspace, XXL scales to realistic manipulator platforms with dozens of joints by focusing the search of the robot’s configuration space to specific degrees-of-freedom that affect motion in particular portions of the workspace. Simulated planning scenarios with the Robonaut2 platform and planar kinematic chains confirm that XXL exhibits competitive solution times relative to many existing works while obtaining execution-quality solution paths. Solutions from XXL are of comparable quality to costaware methods even though XXL does not explicitly optimize over any particular criteria, and are computed in an order of magnitude less time.
- Associated publication:
R. Luna, M. Moll, J. Badger, and L. E. Kavraki, A Scalable Motion Planner for High-Dimensional Kinematic Systems, Intl. J. of Robotics Research, vol. 39, issue 4, pp. 361-388, Mar. 2020. DOI: 10.1177/0278364919890408[PDF]
Public Functions
-
XXL(const base::SpaceInformationPtr &si)
-
XXL(const base::SpaceInformationPtr &si, const XXLDecompositionPtr &decomp)
-
virtual ~XXL()
-
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
-
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
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 clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
-
virtual void setup()
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.
-
void setDecomposition(const XXLDecompositionPtr &decomp)
-
inline double getRandWalkRate() const
-
inline void setRandWalkRate(double rate)
Protected Functions
-
void freeMemory()
-
void updateRegionProperties(const std::vector<int> ®ions)
-
void sampleStates(Layer *layer, const ompl::base::PlannerTerminationCondition &ptc)
-
bool sampleAlongLead(Layer *layer, const std::vector<int> &lead, const ompl::base::PlannerTerminationCondition &ptc)
-
bool feasibleLead(Layer *layer, const std::vector<int> &lead, const ompl::base::PlannerTerminationCondition &ptc)
-
bool connectLead(Layer *layer, const std::vector<int> &lead, std::vector<int> &candidateRegions, const ompl::base::PlannerTerminationCondition &ptc)
-
void connectRegion(Layer *layer, int region, const base::PlannerTerminationCondition &ptc)
-
void connectRegions(Layer *layer, int r1, int r2, const base::PlannerTerminationCondition &ptc, bool all = false)
-
bool searchForPath(Layer *layer, const ompl::base::PlannerTerminationCondition &ptc)
-
void getNeighbors(int rid, const std::vector<double> &weights, std::vector<std::pair<int, double>> &neighbors) const
-
bool shortestPath(int r1, int r2, std::vector<int> &path, const std::vector<double> &weights)
-
bool randomWalk(int r1, int r2, std::vector<int> &path)
-
void getGoalStates()
-
void getGoalStates(const base::PlannerTerminationCondition &ptc)
-
bool constructSolutionPath()
-
bool isStartState(int idx) const
-
bool isGoalState(int idx) const
-
void writeDebugOutput() const
Protected Attributes
-
std::vector<int> startMotions_
-
std::vector<int> goalMotions_
-
std::unordered_map<std::vector<int>, int> goalCount_
-
unsigned int statesConnectedInRealGraph_
-
unsigned int maxGoalStatesPerRegion_
-
unsigned int maxGoalStates_
-
base::StateSamplerPtr sampler_
-
XXLDecompositionPtr decomposition_
-
AdjacencyList lazyGraph_
-
AdjacencyList realGraph_
-
bool kill_ = {false}
-
std::vector<int> predecessors_
-
std::vector<bool> closedList_
-
double rand_walk_rate_ = {-1.0}
-
class Layer
Public Functions
-
inline ~Layer()
-
inline size_t numRegions() const
-
inline int getLevel() const
-
inline int getID() const
-
inline const std::vector<double> &getWeights() const
-
inline std::vector<double> &getWeights()
-
inline const std::vector<bool> &getExterior() const
-
inline std::vector<bool> &getExterior()
-
inline const std::vector<int> &getConnections() const
-
inline const std::vector<int> &getSelections() const
-
inline const std::vector<std::vector<int>> &getGoalStates() const
-
inline const std::vector<int> &getGoalStates(int reg) const
-
inline size_t numGoalStates() const
-
inline size_t numGoalStates(int reg) const
-
inline void addGoalState(int reg, int id)
-
inline AdjacencyList &getRegionGraph()
-
inline const AdjacencyList &getRegionGraph() const
-
inline void allocateSublayers()
-
inline bool hasSublayers()
-
inline void selectRegion(int r, int count = 1)
-
inline void connectRegion(int r)
-
inline int totalSelections() const
-
inline int totalConnections() const
-
inline int connectibleRegions() const
-
inline int connectibleRegion(int idx) const
-
inline int leadAppearances(int idx) const
-
inline int numLeads() const
-
inline void markLead(const std::vector<int> &lead)
Protected Attributes
-
std::vector<double> weights
-
std::vector<bool> exterior
-
std::vector<int> connections
-
std::vector<int> selections
-
std::vector<int> leads
-
std::vector<std::vector<int>> goalStates
-
PerfectSet connectionPoints
-
AdjacencyList *regionGraph
-
int level
-
int numSelections = {0}
-
int numConnections = {0}
-
int id
-
int totalGoalStates = {0}
-
int numTotalLeads = {0}
-
inline ~Layer()
-
struct Motion
-
class PerfectSet
-
struct Region