Class State

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< State >

Class Documentation

class State : public std::enable_shared_from_this<State>

A wrapper class for OMPL’s state.

Public Functions

State(const std::shared_ptr<ompl::base::SpaceInformation> &spaceInfo, const std::shared_ptr<ompl::base::OptimizationObjective> &objective)

Constructs the state, allocating the associated memory using information about the underlying space.

~State()

Destructs this state, freeing the associated memory.

std::size_t getId() const

Returns the state’s unique id.

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

Returns the raw OMPL version of this state.

bool hasForwardVertex() const

Returns whether the state has an associated forward vertex.

bool hasReverseVertex() const

Returns whether the state has an associated reverse vertex.

std::shared_ptr<Vertex> asForwardVertex()

Returns the state as a reverse vertex.

std::shared_ptr<Vertex> asReverseVertex()

Returns the state as a reverse vertex.

void blacklist(const std::shared_ptr<State> &state)

Blacklists the given state as neighbor.

void whitelist(const std::shared_ptr<State> &state)

Whitelists the given state as neighbor.

bool isBlacklisted(const std::shared_ptr<State> &state) const

Returns whether the given state has been blacklisted.

bool isWhitelisted(const std::shared_ptr<State> &state) const

Returns whether the given has been whitelisted.

void setEstimatedEffortToGo(std::size_t effort)

Set the estimated effort (number of collision detections) to go from this state to the goal through the current RGG.

void setEstimatedCostToGo(ompl::base::Cost cost)

Set the best estimate of the cost to go from this state to the goal through the current RGG.

void setAdmissibleCostToGo(ompl::base::Cost cost)

Set the admissible estimate of the cost to go from this state to the goal through the current RGG.

void setLowerBoundCostToGo(ompl::base::Cost cost)

Set the lower bound cost to go from this state to the goal through the continuous state space.

void setLowerBoundCostToCome(ompl::base::Cost cost)

Set the lower bound cost to come from the start to this state through the continuous state space.

void setCurrentCostToCome(ompl::base::Cost cost)

Set the current cost to come from the start to this state.

void setLowerBoundEffortToCome(unsigned int effort)

Sets the lower bound effort to come to this state through the continuous state space.

void setInadmissibleEffortToCome(unsigned int effort)

Sets the inadmissible effort to come to this state through the continuous state space.

unsigned int getEstimatedEffortToGo() const

Get the estimated effort (number of collision detections) to go from this state to the goal through the current RGG.

ompl::base::Cost getEstimatedCostToGo() const

Returns the best estimate of the cost to go from this state to the goal through the current RGG.

ompl::base::Cost getAdmissibleCostToGo() const

Returns the admissible estimate of the cost to go from this state to the goal through the current RGG.

ompl::base::Cost getLowerBoundCostToGo() const

Returns the lower bound cost to go from this state to the goal through the continuous state space.

ompl::base::Cost getLowerBoundCostToCome() const

Returns the lower bound cost to come from the start to this state through the continuous state space.

ompl::base::Cost getCurrentCostToCome() const

Returns the current cost to come from the start to this state.

unsigned int getLowerBoundEffortToCome() const

Returns the lower bound effort to come from the start to this state through the continuous state space.

unsigned int getInadmissibleEffortToCome() const

Returns the inadmissible effort to come from the start to this state through the continuous state space.

const std::vector<std::weak_ptr<State>> getSourcesOfIncomingEdgesInForwardQueue() const

Returns the sources of incoming edges in forward queue.

void addToSourcesOfIncomingEdgesInForwardQueue(const std::shared_ptr<State> &state) const

Adds a source to sources of incoming edges in forward queue.

void removeFromSourcesOfIncomingEdgesInForwardQueue(const std::shared_ptr<State> &state) const

Removes a source from sources of incoming edges in forward queue.

void resetSourcesOfIncomingEdgesInForwardQueue()

Resets the sources of incoming edges in the forward queue.

void setIncomingCollisionCheckResolution(const std::shared_ptr<State> &source, std::size_t numChecks) const

Sets the number of collision checks already performed on the edge incoming from source.

std::size_t getIncomingCollisionCheckResolution(const std::shared_ptr<State> &source) const

Returns the number of collision checks already performed on the edge incoming from source.