Class Vertex

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< Vertex >

Class Documentation

class Vertex : public std::enable_shared_from_this<Vertex>

Public Functions

Vertex(const ompl::base::SpaceInformationPtr &spaceInformation, const ompl::base::ProblemDefinitionPtr &problemDefinition, const std::size_t &batchId)

Constructs a vertex by sampling a state.

explicit Vertex(const std::shared_ptr<Vertex> &other)

Constructs a copy of another vertex.

virtual ~Vertex()

Destructs the vertex.

std::size_t getId() const

Get the unique id of this vertex.

ompl::base::State *getState()

Provides write access to the underlying state.

ompl::base::State const *getState() const

Provides read access to the underlying state.

ompl::base::ScopedState getScopedState() const

Returns a scoped copy of the underlying state.

ompl::base::Cost getCostToComeFromStart() const

Returns the cost to come to this vertex from the start.

ompl::base::Cost getCostToComeFromGoal() const

Returns the cost to come to this vertex from the goal.

ompl::base::Cost getExpandedCostToComeFromGoal() const

Returns the cost to come to this vertex from the goal when it was expanded.

ompl::base::Cost getCostToGoToGoal() const

Returns the cost to go heuristic from this vertex.

ompl::base::Cost getEdgeCostFromForwardParent() const

Returns the edge cost from the forward parent.

bool hasForwardParent() const

Returns whether this vertex has a parent in the forward search.

void setForwardParent(const std::shared_ptr<Vertex> &vertex, const ompl::base::Cost &edgeCost)

Sets the parent vertex (in the forward-search tree).

void resetForwardParent()

Resets the forward parent of the vertex.

bool hasReverseParent() const

Returns whether this vertex has a parent in the reverse search.

void setReverseParent(const std::shared_ptr<Vertex> &vertex)

Sets the parent vertex (in the reverse-search tree).

void resetReverseParent()

Resets the reverse parent of the vertex.

std::shared_ptr<Vertex> getForwardParent() const

Returns the parent of the vertex (in the forward-search tree).

std::shared_ptr<Vertex> getReverseParent() const

Returns the parent of the vertex (in the reverse-search tree).

void setForwardEdgeCost(const ompl::base::Cost &cost)

Sets the cost to come to this vertex.

void setCostToComeFromStart(const ompl::base::Cost &cost)

Sets the cost to come to this vertex.

void setCostToComeFromGoal(const ompl::base::Cost &cost)

Sets the cost to come to this vertex from the goal.

void resetCostToComeFromGoal()

Resets the cost to come to this vertex from the goal to infinity.

void resetExpandedCostToComeFromGoal()

Resets the expanded cost to come to this vertex from the goal to infinity.

void setExpandedCostToComeFromGoal(const ompl::base::Cost &cost)

Sets the cost to come to this vertex from the goal when it was expanded.

void setCostToGoToGoal(const ompl::base::Cost &cost)

Sets the cost to go heuristic of this vertex.

void updateCostOfForwardBranch() const

Updates the cost to the whole branch rooted at this vertex.

std::vector<std::weak_ptr<Vertex>> invalidateReverseBranch()

Recursively invalidates the branch of the reverse tree rooted in this vertex.

std::vector<std::weak_ptr<Vertex>> invalidateForwardBranch()

Recursively invalidates the branch of the forward tree rooted in this vertex.

void addToForwardChildren(const std::shared_ptr<Vertex> &vertex)

Adds a vertex to this vertex’s forward children.

void removeFromForwardChildren(std::size_t vertexId)

Removes a vertex from this vertex’s forward children.

std::vector<std::shared_ptr<Vertex>> getForwardChildren() const

Returns this vertex’s children in the forward search tree.

void addToReverseChildren(const std::shared_ptr<Vertex> &vertex)

Adds a vertex this vertex’s children.

void removeFromReverseChildren(std::size_t vertexId)

Removes a vertex from this vertex’s forward children.

std::vector<std::shared_ptr<Vertex>> getReverseChildren() const

Returns this vertex’s children in the reverse search tree.

void whitelistAsChild(const std::shared_ptr<Vertex> &vertex) const

Whitelists a child.

bool isWhitelistedAsChild(const std::shared_ptr<Vertex> &vertex) const

Returns whether a child is whitelisted.

void blacklistAsChild(const std::shared_ptr<Vertex> &vertex) const

Blacklists a child.

bool isBlacklistedAsChild(const std::shared_ptr<Vertex> &vertex) const

Returns whether a child is blacklisted.

bool hasCachedNeighbors() const

Returns whether the vertex knows its nearest neighbors on the current approximation.

void cacheNeighbors(const std::vector<std::shared_ptr<Vertex>> &neighbors) const

Caches the neighbors for the current approximation.

const std::vector<std::shared_ptr<Vertex>> getNeighbors() const

Returns the nearest neighbors, throws if not up to date.

bool isConsistent() const

Returns whether the vertex is consistent, i.e., whether its cost-to-come is equal to the cost-to-come when it was last expanded.

void setReverseQueuePointer(typename VertexQueue::Element *pointer)

Sets the reverse queue pointer of this vertex.

VertexQueue::Element *getReverseQueuePointer() const

Returns the reverse queue pointer of this vertex.

void resetReverseQueuePointer()

Resets the reverse queue pointer.

void addToForwardQueueIncomingLookup(typename EdgeQueue::Element *pointer)

Adds an element to the forward queue incoming lookup.

void addToForwardQueueOutgoingLookup(typename EdgeQueue::Element *pointer)

Adds an element to the forward queue outgoing lookup.

std::vector<EdgeQueue::Element*> getForwardQueueIncomingLookup() const

Returns the forward queue incoming lookup of this vertex.

std::vector<EdgeQueue::Element*> getForwardQueueOutgoingLookup() const

Returns the forward queue outgoing lookup of this vertex.

void removeFromForwardQueueIncomingLookup(typename EdgeQueue::Element *element)

Remove an element from the incoming queue lookup.

void removeFromForwardQueueOutgoingLookup(typename EdgeQueue::Element *element)

Remove an element from the outgoing queue lookup.

void resetForwardQueueIncomingLookup()

Resets the forward queue incoming lookup.

void resetForwardQueueOutgoingLookup()

Resets the forward queue outgoing lookup.

void callOnForwardBranch(const std::function<void(const std::shared_ptr<Vertex>&)> &function)

Calls the given function on this vertex and all of its children.

void callOnReverseBranch(const std::function<void(const std::shared_ptr<Vertex>&)> &function)

Calls the given function on this vertex and all of its children.