42 # ifdef DEBUG_ESTIMATE_PROPAGATOR 43 struct FrontierLevelCmp {
44 bool operator()(EstimatePropagator::AdjacencyMapEntry* e1, EstimatePropagator::AdjacencyMapEntry* e2)
const 46 return e1->frontierLevel() < e2->frontierLevel();
51 EstimatePropagator::AdjacencyMapEntry::AdjacencyMapEntry()
56 void EstimatePropagator::AdjacencyMapEntry::reset()
61 _distance = numeric_limits<double>::max();
77 for (OptimizableGraph::VertexSet::iterator it=
_visited.begin(); it!=
_visited.end(); ++it){
94 propagate(vset, cost, action, maxDistance, maxEdgeCost);
106 for (OptimizableGraph::VertexSet::iterator vit=vset.begin(); vit!=vset.end(); ++vit){
110 it->second._distance = 0.;
111 it->second._parent.clear();
112 it->second._frontierLevel = 0;
113 frontier.
push(&it->second);
116 while(! frontier.empty()){
119 double uDistance = entry->
distance();
128 OptimizableGraph::EdgeSet::iterator et = u->
edges().begin();
129 while (et != u->
edges().end()){
133 int maxFrontier = -1;
135 for (
size_t i = 0; i < edge->
vertices().size(); ++i) {
138 if (ot->second._distance != numeric_limits<double>::max()) {
139 initializedVertices.insert(z);
140 maxFrontier = (max)(maxFrontier, ot->second._frontierLevel);
143 assert(maxFrontier >= 0);
145 for (
size_t i = 0; i < edge->
vertices().size(); ++i) {
150 size_t wasInitialized = initializedVertices.erase(z);
152 double edgeDistance = cost(edge, initializedVertices, z);
153 if (edgeDistance > 0. && edgeDistance != std::numeric_limits<double>::max() && edgeDistance < maxEdgeCost) {
154 double zDistance = uDistance + edgeDistance;
160 if (zDistance < ot->second.distance() && zDistance < maxDistance){
163 ot->second._distance = zDistance;
164 ot->second._parent = initializedVertices;
165 ot->second._edge = edge;
166 ot->second._frontierLevel = maxFrontier + 1;
167 frontier.
push(&ot->second);
171 if (wasInitialized > 0)
172 initializedVertices.insert(z);
179 #ifdef DEBUG_ESTIMATE_PROPAGATOR 180 cerr <<
"Writing cost.dat" << endl;
181 ofstream costStream(
"cost.dat");
184 costStream <<
"vertex " << u->
id() <<
" cost " << it->second._distance << endl;
186 cerr <<
"Writing init.dat" << endl;
187 ofstream initStream(
"init.dat");
188 vector<AdjacencyMapEntry*> frontierLevels;
190 if (it->second._frontierLevel > 0)
191 frontierLevels.push_back(&it->second);
193 sort(frontierLevels.begin(), frontierLevels.end(), FrontierLevelCmp());
194 for (vector<AdjacencyMapEntry*>::const_iterator it = frontierLevels.begin(); it != frontierLevels.end(); ++it) {
198 initStream <<
"calling init level = " << entry->
_frontierLevel <<
"\t (";
199 for (OptimizableGraph::VertexSet::iterator pit = entry->
parent().begin(); pit != entry->
parent().end(); ++pit) {
200 initStream <<
" " << (*pit)->id();
202 initStream <<
" ) -> " << to->
id() << endl;
210 assert(entry != NULL);
212 assert(entry->
queueIt->second == entry);
217 assert(entry->
queueIt != end());
224 iterator it = begin();
228 assert(entry != NULL);
245 return std::numeric_limits<double>::max();
259 if (std::abs(from->
id() - to->
id()) != 1)
260 return std::numeric_limits<double>::max();
263 return std::numeric_limits<double>::max();
void push(AdjacencyMapEntry *entry)
AdjacencyMap _adjacencyMap
int id() const
returns the id
const Vertex * vertex(size_t i) const
PriorityQueue::iterator queueIt
EstimatePropagatorCost(SparseOptimizer *graph)
AdjacencyMapEntry * pop()
std::set< Vertex * > VertexSet
OptimizableGraph::VertexSet _visited
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Applying the action for propagating.
virtual double operator()(OptimizableGraph::Edge *edge, const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to_) const
const EdgeContainer & activeEdges() const
the edges active in the current optimization
OptimizableGraph * _graph
const VertexIDMap & vertices() const
OptimizableGraph * graph()
data structure for loopuk during Dijkstra
const VertexContainer & vertices() const
const EdgeSet & edges() const
returns the set of hyper-edges that are leaving/entering in this vertex
OptimizableGraph::Vertex * child() const
OptimizableGraph::Vertex * _child
const OptimizableGraph::VertexSet & parent() const
EstimatePropagatorCostOdometry(SparseOptimizer *graph)
void propagate(OptimizableGraph::Vertex *v, const EstimatePropagator::PropagateCost &cost, const EstimatePropagator::PropagateAction &action=PropagateAction(), double maxDistance=std::numeric_limits< double >::max(), double maxEdgeCost=std::numeric_limits< double >::max())
cost for traversing along active edges in the optimizer
OptimizableGraph::Edge * edge() const
A general case Vertex for optimization.
TFSIMD_FORCE_INLINE const tfScalar & z() const
abstract Vertex, your types must derive from that one
EdgeContainer::const_iterator findActiveEdge(const OptimizableGraph::Edge *e) const
virtual double operator()(OptimizableGraph::Edge *edge, const OptimizableGraph::VertexSet &from_, OptimizableGraph::Vertex *to_) const
priority queue for AdjacencyMapEntry