ompl::geometric::aitstar::ImplicitGraph Class Reference
Public Member Functions | |
ImplicitGraph (const ompl::base::Cost &solutionCost) | |
Constructs an implicit graph. | |
virtual | ~ImplicitGraph ()=default |
Destructs an implicit graph. | |
void | setup (const ompl::base::SpaceInformationPtr &spaceInformation, const ompl::base::ProblemDefinitionPtr &problemDefinition, ompl::base::PlannerInputStates *inputStates) |
The setup method for the graph. Needed to have it on the stack. | |
void | clear () |
Resets the graph to its construction state, without resetting options. | |
void | setRewireFactor (double rewireFactor) |
Set the rewire factor of the RGG. | |
double | getRewireFactor () const |
Get the reqire factor of the RGG. | |
void | setMaxNumberOfGoals (unsigned int maxNumberOfGoals) |
Set the maximum number of goals AIT* will sample from sampleable goal regions. | |
unsigned int | getMaxNumberOfGoals () const |
Get the maximum number of goals AIT* will sample from sampleable goal regions. | |
void | setUseKNearest (bool useKNearest) |
Whether to use a k-nearest connection model. If false, it uses an r-disc model. | |
bool | getUseKNearest () const |
Whether the graph uses a k-nearest connection model. If false, it uses an r-disc model. | |
void | setTrackApproximateSolution (bool track) |
Sets whether to track approximate solutions or not. | |
bool | addSamples (std::size_t numNewSamples, const ompl::base::PlannerTerminationCondition &terminationCondition) |
Adds a batch of samples and returns the samples it has added. | |
std::size_t | getNumVertices () const |
Gets the number of samples in the graph. | |
double | getConnectionRadius () const |
Gets the RGG connection radius. | |
void | registerStartState (const ompl::base::State *const startState) |
Registers a state as a start state. | |
void | registerGoalState (const ompl::base::State *const goalState) |
Registers a state as a goal state. | |
bool | hasAStartState () const |
Returns whether the graph has a goal state. | |
bool | hasAGoalState () const |
Returns whether the graph has a goal state. | |
void | updateStartAndGoalStates (const ompl::base::PlannerTerminationCondition &terminationCondition, ompl::base::PlannerInputStates *inputStates) |
Adds new start and goals to the graph if avavilable and creates a new informed sampler if necessary. | |
std::vector< std::shared_ptr< Vertex > > | getNeighbors (const std::shared_ptr< Vertex > &vertex) const |
Get neighbors of a vertex. | |
bool | isStart (const std::shared_ptr< Vertex > &vertex) const |
Checks whether the vertex is a start vertex. | |
bool | isGoal (const std::shared_ptr< Vertex > &vertex) const |
Checks whether the vertex is a goal vertex. | |
const std::vector< std::shared_ptr< Vertex > > & | getStartVertices () const |
Get the start vertices. | |
const std::vector< std::shared_ptr< Vertex > > & | getGoalVertices () const |
Get the goal vertices. | |
std::vector< std::shared_ptr< Vertex > > | getVertices () const |
Get all vertices. | |
void | prune () |
Prune all samples that can not contribute to a solution better than the current one. | |
std::size_t | getNumberOfSampledStates () const |
Returns the total number of sampled states. | |
std::size_t | getNumberOfValidSamples () const |
Returns the total number of valid samples found. | |
std::size_t | getNumberOfStateCollisionChecks () const |
Get the number of state collision checks. | |
std::size_t | getNumberOfNearestNeighborCalls () const |
Get the number of nearest neighbor calls. | |
Detailed Description
Definition at line 154 of file ImplicitGraph.h.
The documentation for this class was generated from the following files:
- ompl/geometric/planners/informedtrees/aitstar/ImplicitGraph.h
- ompl/geometric/planners/informedtrees/aitstar/src/ImplicitGraph.cpp