PlannerData.cpp
54 const ompl::base::PlannerDataEdge ompl::base::PlannerData::NO_EDGE = ompl::base::PlannerDataEdge();
55 const ompl::base::PlannerDataVertex ompl::base::PlannerData::NO_VERTEX = ompl::base::PlannerDataVertex(nullptr);
56 const unsigned int ompl::base::PlannerData::INVALID_INDEX = std::numeric_limits<unsigned int>::max();
102 unsigned int ompl::base::PlannerData::getEdges(unsigned int v, std::vector<unsigned int> &edgeList) const
108 boost::property_map<Graph::Type, boost::vertex_index_t>::type vertices = get(boost::vertex_index, *graph_);
118 std::pair<Graph::OEIterator, Graph::OEIterator> iterators = boost::out_edges(boost::vertex(v, *graph_), *graph_);
122 boost::property_map<Graph::Type, boost::vertex_index_t>::type vertices = get(boost::vertex_index, *graph_);
129 unsigned int ompl::base::PlannerData::getIncomingEdges(unsigned int v, std::vector<unsigned int> &edgeList) const
131 std::pair<Graph::IEIterator, Graph::IEIterator> iterators = boost::in_edges(boost::vertex(v, *graph_), *graph_);
134 boost::property_map<Graph::Type, boost::vertex_index_t>::type vertices = get(boost::vertex_index, *graph_);
144 std::pair<Graph::IEIterator, Graph::IEIterator> iterators = boost::in_edges(boost::vertex(v, *graph_), *graph_);
148 boost::property_map<Graph::Type, boost::vertex_index_t>::type vertices = get(boost::vertex_index, *graph_);
155 bool ompl::base::PlannerData::getEdgeWeight(unsigned int v1, unsigned int v2, Cost *weight) const
159 boost::tie(e, exists) = boost::edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), *graph_);
163 boost::property_map<Graph::Type, boost::edge_weight_t>::type edges = get(boost::edge_weight, *graph_);
175 boost::tie(e, exists) = boost::edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), *graph_);
179 boost::property_map<Graph::Type, boost::edge_weight_t>::type edges = get(boost::edge_weight, *graph_);
191 boost::tie(e, exists) = boost::edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), *graph_);
210 const ompl::base::PlannerDataVertex &ompl::base::PlannerData::getVertex(unsigned int index) const
228 const ompl::base::PlannerDataEdge &ompl::base::PlannerData::getEdge(unsigned int v1, unsigned int v2) const
232 boost::tie(e, exists) = boost::edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), *graph_);
247 boost::tie(e, exists) = boost::edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), *graph_);
299 boost::function_property_map<std::function<std::string(Vertex)>, Vertex> coordsmap([this, &s](Vertex v)
357 const ompl::base::PlannerDataVertex &ompl::base::PlannerData::getStartVertex(unsigned int i) const
373 const ompl::base::PlannerDataVertex &ompl::base::PlannerData::getGoalVertex(unsigned int i) const
430 bool ompl::base::PlannerData::addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge, Cost weight)
446 tie(e, added) = boost::add_edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), properties, *graph_);
485 boost::property_map<Graph::Type, edge_type_t>::type edgePropertyMap = get(edge_type_t(), *graph_);
531 boost::property_map<Graph::Type, vertex_type_t>::type vertexTypeMap = get(vertex_type_t(), *graph_);
542 boost::tie(e, exists) = boost::edge(boost::vertex(v1, *graph_), boost::vertex(v2, *graph_), *graph_);
555 bool ompl::base::PlannerData::removeEdge(const PlannerDataVertex &v1, const PlannerDataVertex &v2)
623 setEdgeWeight(i, it->first, opt.motionCost(getVertex(i).getState(), getVertex(it->first).getState()));
636 void ompl::base::PlannerData::extractMinimumSpanningTree(unsigned int v, const base::OptimizationObjective &opt,
bool edgeExists(unsigned int v1, unsigned int v2) const
Check whether an edge between vertex index v1 and index v2 exists.
Definition: PlannerData.cpp:186
unsigned int numGoalVertices() const
Returns the number of goal vertices.
Definition: PlannerData.cpp:326
bool getEdgeWeight(unsigned int v1, unsigned int v2, Cost *weight) const
Returns the weight of the edge between the given vertex indices. If there exists an edge between v1 a...
Definition: PlannerData.cpp:155
virtual Cost identityCost() const
Get the identity cost value. The identity cost value is the cost c_i such that, for all costs c,...
Definition: OptimizationObjective.cpp:106
unsigned int getStartIndex(unsigned int i) const
Returns the index of the ith start state. INVALID_INDEX is returned if i is out of range....
Definition: PlannerData.cpp:331
virtual bool removeEdge(unsigned int v1, unsigned int v2)
Removes the edge between vertex indexes v1 and v2. Success is returned.
Definition: PlannerData.cpp:538
A shared pointer wrapper for ompl::base::SpaceInformation.
virtual PlannerDataEdge * clone() const
Return a clone of this object, allocated from the heap.
Definition: PlannerData.h:196
unsigned int getEdges(unsigned int v, std::vector< unsigned int > &edgeList) const
Returns a list of the vertex indexes directly connected to vertex with index v (outgoing edges)....
Definition: PlannerData.cpp:102
Representation of a space in which planning can be performed. Topology specific sampling,...
Definition: StateSpace.h:134
const SpaceInformationPtr & getSpaceInformation() const
Return the instance of SpaceInformation used in this PlannerData.
Definition: PlannerData.cpp:755
bool isStartVertex(unsigned int index) const
Returns true if the given vertex index is marked as a start vertex.
Definition: PlannerData.cpp:347
Wrapper class for the Boost.Graph representation of the PlannerData. This class inherits from a boost...
Definition: PlannerDataGraph.h:72
An optimization objective which corresponds to optimizing path length.
Definition: PathLengthOptimizationObjective.h:111
bool isGoalVertex(unsigned int index) const
Returns true if the given vertex index is marked as a goal vertex.
Definition: PlannerData.cpp:352
static const PlannerDataEdge NO_EDGE
Representation for a non-existant edge.
Definition: PlannerData.h:241
virtual PlannerDataVertex * clone() const
Return a clone of this object, allocated from the heap.
Definition: PlannerData.h:182
bool vertexExists(const PlannerDataVertex &v) const
Check whether a vertex exists with the given vertex data.
Definition: PlannerData.cpp:195
void printPLY(std::ostream &out, bool asIs=false) const
Write a mesh of the planner graph to a stream. Insert additional vertices if asIs == true.
Definition: PlannerData.cpp:787
virtual Cost infiniteCost() const
Get a cost which is greater than all other costs in this OptimizationObjective; required for use in D...
Definition: OptimizationObjective.cpp:111
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:111
bool tagState(const State *st, int tag)
Set the integer tag associated with the given state. If the given state does not exist in a vertex,...
Definition: PlannerData.cpp:567
virtual void decoupleFromPlanner()
Creates a deep copy of the states contained in the vertices of this PlannerData structure so that whe...
Definition: PlannerData.cpp:80
unsigned int numEdges() const
Retrieve the number of edges in this structure.
Definition: PlannerData.cpp:205
StateStoragePtr extractStateStorage() const
Extract a ompl::base::GraphStateStorage object from this PlannerData. Memory for states is copied (th...
Definition: PlannerData.cpp:714
boost::graph_traits< Type >::vertex_descriptor Vertex
Boost.Graph vertex descriptor.
Definition: PlannerDataGraph.h:111
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
static const unsigned int INVALID_INDEX
Representation of an invalid vertex index.
Definition: PlannerData.h:248
Abstract definition of optimization objectives.
Definition: OptimizationObjective.h:138
void printGraphML(std::ostream &out=std::cout) const
Writes a GraphML file of this structure to the given stream.
Definition: PlannerData.cpp:282
unsigned int numVertices() const
Retrieve the number of vertices in this structure.
Definition: PlannerData.cpp:200
unsigned int numStartVertices() const
Returns the number of start vertices.
Definition: PlannerData.cpp:321
unsigned int vertexIndex(const PlannerDataVertex &v) const
Return the index for the vertex associated with the given data. INVALID_INDEX is returned if this ver...
Definition: PlannerData.cpp:313
const PlannerDataVertex & getStartVertex(unsigned int i) const
Retrieve a reference to the ith start vertex object. If i is greater than the number of start vertice...
Definition: PlannerData.cpp:357
bool setEdgeWeight(unsigned int v1, unsigned int v2, Cost weight)
Sets the weight of the edge between the given vertex indices. If an edge between v1 and v2 does not e...
Definition: PlannerData.cpp:171
virtual Cost motionCost(const State *s1, const State *s2) const =0
Get the cost that corresponds to the motion segment between s1 and s2.
bool markGoalState(const State *st)
Mark the given state as a goal vertex. If the given state does not exist in a vertex,...
Definition: PlannerData.cpp:595
void printGraphviz(std::ostream &out=std::cout) const
Writes a Graphviz dot file of this structure to the given stream.
Definition: PlannerData.cpp:258
void extractReachable(unsigned int v, PlannerData &data) const
Extracts the subset of PlannerData reachable from the vertex with index v. For tree structures,...
Definition: PlannerData.cpp:683
const PlannerDataVertex & getVertex(unsigned int index) const
Retrieve a reference to the vertex object with the given index. If this vertex does not exist,...
Definition: PlannerData.cpp:210
virtual const State * getState() const
Retrieve the state associated with this vertex.
Definition: PlannerData.h:176
bool markStartState(const State *st)
Mark the given state as a start vertex. If the given state does not exist in a vertex,...
Definition: PlannerData.cpp:578
virtual bool removeVertex(const PlannerDataVertex &st)
Removes the vertex associated with the given data. If the vertex does not exist, false is returned....
Definition: PlannerData.cpp:471
virtual bool isCostBetterThan(Cost c1, Cost c2) const
Check whether the the cost c1 is considered better than the cost c2. By default, this returns true if...
Definition: OptimizationObjective.cpp:70
unsigned int addVertex(const PlannerDataVertex &st)
Adds the given vertex to the graph data. The vertex index is returned. Duplicates are not added....
Definition: PlannerData.cpp:389
const PlannerDataVertex & getGoalVertex(unsigned int i) const
Retrieve a reference to the ith goal vertex object. If i is greater than the number of goal vertices,...
Definition: PlannerData.cpp:373
void extractMinimumSpanningTree(unsigned int v, const OptimizationObjective &opt, PlannerData &mst) const
Extracts the minimum spanning tree of the data rooted at the vertex with index v. The minimum spannin...
Definition: PlannerData.cpp:636
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition: PlannerData.cpp:411
void computeEdgeWeights()
Computes all edge weights using state space distance (i.e. getSpaceInformation()->distance())
Definition: PlannerData.cpp:628
unsigned int getIncomingEdges(unsigned int v, std::vector< unsigned int > &edgeList) const
Returns a list of vertices with outgoing edges to the vertex with index v. The number of edges connec...
Definition: PlannerData.cpp:129
static const PlannerDataVertex NO_VERTEX
Representation for a non-existant vertex.
Definition: PlannerData.h:246
boost::graph_traits< Type >::edge_descriptor Edge
Boost.Graph edge descriptor.
Definition: PlannerDataGraph.h:113
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
Definition: PlannerData.cpp:430
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition: PlannerData.cpp:420
Graph & toBoostGraph()
Extract a Boost.Graph object from this PlannerData.
Definition: PlannerData.cpp:742
PlannerDataGraph Type
Data type for the Boost.Graph representation.
Definition: PlannerDataGraph.h:108
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122
virtual bool hasControls() const
Indicate whether any information about controls (ompl::control::Control) is stored in this instance.
Definition: PlannerData.cpp:782
const PlannerDataEdge & getEdge(unsigned int v1, unsigned int v2) const
Retrieve a reference to the edge object connecting vertices with indexes v1 and v2....
Definition: PlannerData.cpp:228
unsigned int getGoalIndex(unsigned int i) const
Returns the index of the ith goal state. INVALID_INDEX is returned if i is out of range Indexes are v...
Definition: PlannerData.cpp:339