ed
world_model.cpp
Go to the documentation of this file.
1 #include "ed/world_model.h"
2 
3 #include "ed/update_request.h"
4 #include "ed/entity.h"
5 #include "ed/relation.h"
6 
7 #include <tue/config/reader.h>
8 #include <boost/make_shared.hpp>
9 
10 #include "ed/property_key_db.h"
11 
12 namespace ed
13 {
14 
15 // --------------------------------------------------------------------------------
16 
17 WorldModel::WorldModel(const PropertyKeyDB* prop_key_db) : revision_(0), property_info_db_(prop_key_db)
18 {
19 }
20 
21 // --------------------------------------------------------------------------------
22 
24 {
25  if (req.empty())
26  return;
27 
28  // Increase revision number
29  ++revision_;
30 
31  std::map<UUID, EntityPtr> new_entities;
32 
33  // Update associated measurements
34  for(std::map<UUID, std::vector<MeasurementConstPtr> >::const_iterator it = req.measurements.begin(); it != req.measurements.end(); ++it)
35  {
36  EntityPtr e = getOrAddEntity(it->first, new_entities);
37  const std::vector<MeasurementConstPtr>& measurements = it->second;
38  for(std::vector<MeasurementConstPtr>::const_iterator it2 = measurements.begin(); it2 != measurements.end(); ++it2)
39  {
40  e->addMeasurement(*it2);
41  }
42  }
43 
44  // Update poses
45  for(std::map<UUID, geo::Pose3D>::const_iterator it = req.poses.begin(); it != req.poses.end(); ++it)
46  {
47  EntityPtr e = getOrAddEntity(it->first, new_entities);
48  e->setPose(it->second);
49  }
50 
51  for (const UUID& id : req.poses_removed)
52  {
53  EntityPtr e = getOrAddEntity(id, new_entities);
54  e->removePose();
55  }
56 
57  // Update visuals
58  for(std::map<UUID, geo::ShapeConstPtr>::const_iterator it = req.visuals.begin(); it != req.visuals.end(); ++it)
59  {
60  EntityPtr e = getOrAddEntity(it->first, new_entities);
61  e->setVisual(it->second);
62 
63  Idx idx;
64  if (findEntityIdx(e->id(), idx))
65  {
67  }
68  }
69 
70  // Update collisions
71  for(std::map<UUID, geo::ShapeConstPtr>::const_iterator it = req.collisions.begin(); it != req.collisions.end(); ++it)
72  {
73  EntityPtr e = getOrAddEntity(it->first, new_entities);
74  e->setCollision(it->second);
75 
76  Idx idx;
77  if (findEntityIdx(e->id(), idx))
78  {
80  }
81  }
82 
83  // Update convex hulls new
85  {
86  EntityPtr e = getOrAddEntity(it->first, new_entities);
87  for(std::map<std::string, ed::MeasurementConvexHull>::const_iterator it2 = it->second.begin(); it2 != it->second.end(); ++it2)
88  {
89  const ed::MeasurementConvexHull& m = it2->second;
90  e->setConvexHull(m.convex_hull, m.pose, m.timestamp, it2->first);
91  }
92 
93  Idx idx;
94  if (findEntityIdx(e->id(), idx))
95  {
98  }
99  }
100 
101  // Update volumes
102  for (std::map<UUID, std::set<std::string> >::const_iterator it = req.volumes_removed.begin(); it != req.volumes_removed.end(); ++it )
103  {
104  EntityPtr e = getOrAddEntity(it->first, new_entities);
105  const std::set<std::string>& volume_names = it->second;
106  for (std::set<std::string>::const_iterator it2 = volume_names.begin(); it2 != volume_names.end(); ++it2)
107  e->removeVolume(*it2);
108  Idx idx;
109  if (findEntityIdx(e->id(), idx))
110  {
112  }
113  }
114  for (std::map<UUID, std::map<std::string, geo::ShapeConstPtr> >::const_iterator it = req.volumes_added.begin(); it != req.volumes_added.end(); ++it)
115  {
116  EntityPtr e = getOrAddEntity(it->first, new_entities);
117  const std::map<std::string, geo::ShapeConstPtr>& volumes = it->second;
118  for (std::map<std::string, geo::ShapeConstPtr>::const_iterator it2 = volumes.begin(); it2 != volumes.end(); ++it2)
119  {
120  e->addVolume(it2->first, it2->second);
121  }
122  Idx idx;
123  if (findEntityIdx(e->id(), idx))
124  {
126  }
127  }
128 
129  // Update types
130  for(std::map<UUID, std::string>::const_iterator it = req.types.begin(); it != req.types.end(); ++it)
131  {
132  EntityPtr e = getOrAddEntity(it->first, new_entities);
133  e->setType(it->second);
134  }
135 
136  for(std::map<UUID, std::set<std::string> >::const_iterator it = req.type_sets_added.begin(); it != req.type_sets_added.end(); ++it)
137  {
138  EntityPtr e = getOrAddEntity(it->first, new_entities);
139  const std::set<std::string>& type_set = it->second;
140  for(std::set<std::string>::const_iterator it2 = type_set.begin(); it2 != type_set.end(); ++it2)
141  e->addType(*it2);
142  }
143 
144  for(std::map<UUID, std::set<std::string> >::const_iterator it = req.type_sets_removed.begin(); it != req.type_sets_removed.end(); ++it)
145  {
146  EntityPtr e = getOrAddEntity(it->first, new_entities);
147  const std::set<std::string>& type_set = it->second;
148  for(std::set<std::string>::const_iterator it2 = type_set.begin(); it2 != type_set.end(); ++it2)
149  e->removeType(*it2);
150  }
151 
152  // Update existence probabilities
154  {
155  EntityPtr e = getOrAddEntity(it->first, new_entities);
156  e->setExistenceProbability(it->second);
157  }
158 
159  // Update last update timestamps
161  {
162  EntityPtr e = getOrAddEntity(it->first, new_entities);
163  e->setLastUpdateTimestamp(it->second);
164  }
165 
166  // Update relations
167  for(std::map<UUID, std::map<UUID, RelationConstPtr> >::const_iterator it = req.relations.begin(); it != req.relations.end(); ++it)
168  {
169  Idx idx1;
170  if (findEntityIdx(it->first, idx1))
171  {
172  const std::map<UUID, RelationConstPtr>& rels = it->second;
173  for(std::map<UUID, RelationConstPtr>::const_iterator it2 = rels.begin(); it2 != rels.end(); ++it2)
174  {
175  Idx idx2;
176  if (findEntityIdx(it2->first, idx2))
177  setRelation(idx1, idx2, it2->second);
178  else
179  std::cout << "WorldModel::update (relation): unknown entity: '" << it2->first << "'." << std::endl;
180  }
181  }
182  else
183  std::cout << "WorldModel::update (relation): unknown entity: '" << it->first << "'." << std::endl;
184  }
185 
186  // Update flags
188  {
189  EntityPtr e = getOrAddEntity(it->first, new_entities);
190  e->setFlag(it->second);
191  }
192 
194  {
195  EntityPtr e = getOrAddEntity(it->first, new_entities);
196  e->removeFlag(it->second);
197  }
198 
199  // Update additional info (data)
200  for(std::map<UUID, tue::config::DataConstPointer>::const_iterator it = req.datas.begin(); it != req.datas.end(); ++it)
201  {
202  EntityPtr e = getOrAddEntity(it->first, new_entities);
203 
205  params.add(e->data());
206  params.add(it->second);
207 
208  e->setData(params);
209  }
210 
211  for(std::map<UUID, std::map<Idx, Property> >::const_iterator it = req.properties.begin(); it != req.properties.end(); ++it)
212  {
213  EntityPtr e = getOrAddEntity(it->first, new_entities);
214  const std::map<Idx, Property>& props = it->second;
215 
216  for(std::map<Idx, Property>::const_iterator it2 = props.begin(); it2 != props.end(); ++it2)
217  {
218  const Property& p = it2->second;
219  e->setProperty(it2->first, p);
220  }
221  }
222 
223  // Remove entities
224  for(std::set<UUID>::const_iterator it = req.removed_entities.begin(); it != req.removed_entities.end(); ++it)
225  {
226  removeEntity(*it);
227  }
228 }
229 
230 // --------------------------------------------------------------------------------
231 
233 {
235 
236  SearchNode(Idx parent_, Idx relation_, bool inverse_)
237  : parent(parent_), relation(relation_), inverse(inverse_) {}
238 
241  bool inverse;
242 };
243 
244 // --------------------------------------------------------------------------------
245 
246 bool WorldModel::calculateTransform(const UUID& source, const UUID& target, const Time& time, geo::Pose3D& tf) const
247 {
248  Idx s, t;
249  if (!findEntityIdx(source, s) || !findEntityIdx(target, t))
250  return false;
251 
252  std::queue<Idx> Q;
254 
255  Q.push(s);
256  visited[s] = SearchNode(INVALID_IDX, INVALID_IDX, true);
257 
258  while(!Q.empty())
259  {
260  Idx n = Q.front();
261  Q.pop();
262 
263  if (n == t)
264  {
265  // Calculate transformation
266  tf = geo::Pose3D::identity();
267 
268  Idx u = n;
269 
270  while (u != s)
271  {
273  const SearchNode& sn = it->second;
274 
275  const RelationConstPtr& r = relations_[sn.relation];
276 
277  geo::Pose3D tr;
278  if (!r->calculateTransform(time, tr))
279  {
280  std::cout << "WorldModel::calculateTransform: transform could not be calculated. THIS SHOULD NEVER HAPPEN!" << std::endl;
281  return false;
282  }
283 
284  if (sn.inverse)
285  tf = tr.inverse() * tf;
286  else
287  tf = tr * tf;
288 
289  u = sn.parent;
290  }
291 
292  return true;
293  }
294 
295  // Push all nodes that point to this node
296  const std::map<Idx, Idx>& transforms_to = entities_[n]->relationsTo();
297  for(std::map<Idx, Idx>::const_iterator it = transforms_to.begin(); it != transforms_to.end(); ++it)
298  {
299  Idx n2 = it->first;
300  if (visited.find(n2) == visited.end())
301  {
302  visited[n2] = SearchNode(n, it->second, false);
303  Q.push(n2);
304  }
305  }
306 
307  // Push all nodes this node points to
308  const std::map<Idx, Idx>& transforms_from = entities_[n]->relationsFrom();
309  for(std::map<Idx, Idx>::const_iterator it = transforms_from.begin(); it != transforms_from.end(); ++it)
310  {
311  Idx n2 = it->first;
312  if (visited.find(n2) == visited.end())
313  {
314  visited[n2] = SearchNode(n, it->second, true);
315  Q.push(n2);
316  }
317  }
318  }
319 
320  return false;
321 }
322 
323 // --------------------------------------------------------------------------------
324 
325 void WorldModel::setRelation(Idx parent, Idx child, const RelationConstPtr& r)
326 {
327  const EntityConstPtr& p = entities_[parent];
328  const EntityConstPtr& c = entities_[child];
329 
330  if (!p || !c)
331  {
332  std::cout << "[ED] ERROR: Invalid relation addition: parent or child does not exit." << std::endl;
333  return;
334  }
335 
336  Idx r_idx = p->relationTo(child);
337  if (r_idx == INVALID_IDX)
338  {
339  r_idx = addRelation(r);
340 
341  EntityPtr p_new(new Entity(*entities_[parent]));
342  EntityPtr c_new(new Entity(*entities_[child]));
343 
344  p_new->setRelationTo(child, r_idx);
345  c_new->setRelationFrom(parent, r_idx);
346 
347  entities_[parent] = p_new;
348  entities_[child] = c_new;
349  }
350  else
351  {
352  relations_[r_idx] = r;
353  }
354 
355  // Update entity revisions
356  for(std::size_t i = entity_revisions_.size(); i < std::max(parent, child) + 1; ++i)
358  entity_revisions_[parent] = revision_;
359  entity_revisions_[child] = revision_;
360 }
361 
362 // --------------------------------------------------------------------------------
363 
365 {
366  Idx r_idx = relations_.size();
368  return r_idx;
369 }
370 
371 // --------------------------------------------------------------------------------
372 
373 void WorldModel::setEntity(const UUID& id, const EntityConstPtr& e)
374 {
376  if (it_idx == entity_map_.end())
377  {
378  addNewEntity(e);
379  }
380  else
381  {
382  entities_[it_idx->second] = e;
383  }
384 }
385 
386 // --------------------------------------------------------------------------------
387 
389 {
390  std::map<UUID, Idx>::iterator it_idx = entity_map_.find(id);
391  if (it_idx != entity_map_.end())
392  {
393  entities_[it_idx->second].reset();
394  entity_revisions_[it_idx->second] = revision_;
395  entity_visual_revisions_[it_idx->second] = 0;
396  entity_collision_revisions_[it_idx->second] = 0;
397  entity_volumes_revisions_[it_idx->second] = 0;
398  entity_empty_spots_.push(it_idx->second);
399  entity_map_.erase(it_idx);
400  }
401 }
402 
403 // --------------------------------------------------------------------------------
404 
406 {
407  // Check if the id is already in the new_entities map. If so, return it
408  std::map<UUID, EntityPtr>::const_iterator it_e = new_entities.find(id);
409  if (it_e != new_entities.end())
410  return it_e->second;
411 
412  EntityPtr e;
413 
414  Idx idx;
415  if (findEntityIdx(id, idx))
416  {
417  // Create a copy of the existing entity
418  e = boost::make_shared<Entity>(*entities_[idx]);
419 
420  // Set the copy
421  entities_[idx] = e;
422  }
423  else
424  {
425  // Does not yet exist
426  e = boost::make_shared<Entity>(id);
427  idx = addNewEntity(e);
428  }
429 
430  // Update entity revision
431  e->setRevision(revision_);
432 
433  new_entities[id] = e;
434 
435  for(std::size_t i = entity_revisions_.size(); i < idx + 1; ++i)
438 
439  return e;
440 }
441 
442 // --------------------------------------------------------------------------------
443 
444 bool WorldModel::findEntityIdx(const UUID& id, Idx& idx) const
445 {
446  if (id.idx != INVALID_IDX && entities_[id.idx] && entities_[id.idx]->id() == id.str())
447  {
448  idx = id.idx;
449  return true;
450  }
451 
453  if (it == entity_map_.end())
454  return false;
455 
456  idx = it->second;
457  id.idx = idx;
458  return true;
459 }
460 
461 // --------------------------------------------------------------------------------
462 
464 {
465  Idx idx;
467  {
468  idx = entities_.size();
469  entity_map_[e->id()] = idx;
470  entities_.push_back(e);
474  }
475  else
476  {
477  idx = entity_empty_spots_.front();
479  entity_map_[e->id()] = idx;
480  entities_[idx] = e;
481  }
482 
483  return idx;
484 }
485 
486 // --------------------------------------------------------------------------------
487 
489 {
490  if (!property_info_db_)
491  return nullptr;
492 
494 }
495 
496 }
497 
498 
ed::UpdateRequest::measurements
std::map< UUID, std::vector< MeasurementConstPtr > > measurements
Definition: update_request.h:34
ed::UpdateRequest::types
std::map< UUID, std::string > types
Definition: update_request.h:105
ed::WorldModel::entity_volumes_revisions_
std::vector< unsigned long > entity_volumes_revisions_
Definition: world_model.h:130
ed::UpdateRequest
Definition: update_request.h:24
ed::UpdateRequest::visuals
std::map< UUID, geo::ShapeConstPtr > visuals
Definition: update_request.h:50
ed::WorldModel::WorldModel
WorldModel(const PropertyKeyDB *prop_key_db=nullptr)
Definition: world_model.cpp:17
std::string
ed::WorldModel::revision_
unsigned long revision_
Definition: world_model.h:118
entity.h
t
Timer t
ed::WorldModel::entity_revisions_
std::vector< unsigned long > entity_revisions_
Definition: world_model.h:124
geo::Transform3T::identity
static Transform3T identity()
ed::WorldModel::addRelation
Idx addRelation(const RelationConstPtr &r)
Definition: world_model.cpp:364
ed::WorldModel::entities_
std::vector< EntityConstPtr > entities_
Definition: world_model.h:122
std::vector
std::map::find
T find(T... args)
std::vector::size
T size(T... args)
property_key_db.h
ed::WorldModel::property_info_db_
const PropertyKeyDB * property_info_db_
Definition: world_model.h:136
tue::config::DataPointer
ed::UpdateRequest::properties
std::map< UUID, std::map< Idx, Property > > properties
Definition: update_request.h:167
reader.h
ed::WorldModel::entity_visual_revisions_
std::vector< unsigned long > entity_visual_revisions_
Definition: world_model.h:126
ed::SearchNode::SearchNode
SearchNode(Idx parent_, Idx relation_, bool inverse_)
Definition: world_model.cpp:236
geo::Transform3T
relation.h
ed::Time
Definition: time.h:9
ed::WorldModel::getPropertyInfo
const PropertyKeyDBEntry * getPropertyInfo(const std::string &name) const
Definition: world_model.cpp:488
ed::UpdateRequest::type_sets_removed
std::map< UUID, std::set< std::string > > type_sets_removed
Definition: update_request.h:111
std::queue< Idx >
ed::UpdateRequest::last_update_timestamps
std::map< UUID, double > last_update_timestamps
Definition: update_request.h:124
std::queue::front
T front(T... args)
ed::WorldModel::update
void update(const UpdateRequest &req)
Definition: world_model.cpp:23
ed::UpdateRequest::volumes_added
std::map< UUID, std::map< std::string, geo::ShapeConstPtr > > volumes_added
Definition: update_request.h:60
ed::EntityConstPtr
shared_ptr< const Entity > EntityConstPtr
Definition: types.h:37
std::vector::push_back
T push_back(T... args)
std::cout
ed::WorldModel::removeEntity
void removeEntity(const UUID &id)
Definition: world_model.cpp:388
geo::Transform3T::inverse
Transform3T inverse() const
ed::WorldModel::entity_collision_revisions_
std::vector< unsigned long > entity_collision_revisions_
Definition: world_model.h:128
ed::WorldModel::setRelation
void setRelation(Idx parent, Idx child, const RelationConstPtr &r)
Definition: world_model.cpp:325
ed::MeasurementConvexHull::convex_hull
ConvexHull convex_hull
Definition: measurement_convex_hull.h:12
ed::UpdateRequest::relations
std::map< UUID, std::map< UUID, RelationConstPtr > > relations
Definition: update_request.h:140
ed::WorldModel::entity_map_
std::map< UUID, Idx > entity_map_
Definition: world_model.h:120
update_request.h
ed::WorldModel::getOrAddEntity
EntityPtr getOrAddEntity(const UUID &id, std::map< UUID, EntityPtr > &new_entities)
Definition: world_model.cpp:405
ed::UpdateRequest::type_sets_added
std::map< UUID, std::set< std::string > > type_sets_added
Definition: update_request.h:108
ed::Entity
Definition: entity.h:30
std::queue::pop
T pop(T... args)
ed::SearchNode::SearchNode
SearchNode()
Definition: world_model.cpp:234
ed::WorldModel::calculateTransform
bool calculateTransform(const UUID &source, const UUID &target, const Time &time, geo::Pose3D &tf) const
Definition: world_model.cpp:246
ed::MeasurementConvexHull
Definition: measurement_convex_hull.h:10
ed::UpdateRequest::added_flags
std::map< ed::UUID, std::string > added_flags
Definition: update_request.h:199
ed::WorldModel::entity_empty_spots_
std::queue< Idx > entity_empty_spots_
Definition: world_model.h:132
ed::PropertyKeyDBEntry
Definition: property_key_db.h:13
ed::PropertyKeyDB
Definition: property_key_db.h:28
ed::INVALID_IDX
static const Idx INVALID_IDX
Definition: types.h:22
ed::UpdateRequest::convex_hulls_new
std::map< UUID, std::map< std::string, ed::MeasurementConvexHull > > convex_hulls_new
Definition: update_request.h:86
ed::UUID
Definition: uuid.h:10
std::map
ed::UpdateRequest::removed_entities
std::set< UUID > removed_entities
Definition: update_request.h:192
ed::MeasurementConvexHull::timestamp
double timestamp
Definition: measurement_convex_hull.h:14
ed::WorldModel::EntityIterator
Definition: world_model.h:26
ed::WorldModel::relations_
std::vector< RelationConstPtr > relations_
Definition: world_model.h:134
ed::SearchNode::relation
Idx relation
Definition: world_model.cpp:240
std::endl
T endl(T... args)
ed::UpdateRequest::poses
std::map< UUID, geo::Pose3D > poses
Definition: update_request.h:131
std::vector::begin
T begin(T... args)
ed::MeasurementConvexHull::pose
geo::Pose3D pose
Definition: measurement_convex_hull.h:13
tue::config::DataPointer::add
bool add(const DataConstPointer &ptr)
ed::WorldModel::findEntityIdx
bool findEntityIdx(const UUID &id, Idx &idx) const
Definition: world_model.cpp:444
ed::UpdateRequest::removed_flags
std::map< ed::UUID, std::string > removed_flags
Definition: update_request.h:203
ed::UpdateRequest::empty
bool empty() const
Definition: update_request.h:213
std::queue::empty
T empty(T... args)
std::queue::push
T push(T... args)
ed
Definition: convex_hull.h:8
std::size_t
ed::RelationConstPtr
shared_ptr< const Relation > RelationConstPtr
Definition: types.h:73
std::vector::end
T end(T... args)
ed::UpdateRequest::volumes_removed
std::map< UUID, std::set< std::string > > volumes_removed
Definition: update_request.h:80
ed::WorldModel::setEntity
void setEntity(const UUID &id, const EntityConstPtr &e)
Definition: world_model.cpp:373
ed::SearchNode::parent
Idx parent
Definition: world_model.cpp:239
ed::UpdateRequest::collisions
std::map< UUID, geo::ShapeConstPtr > collisions
Definition: update_request.h:56
std::max
T max(T... args)
ed::UpdateRequest::existence_probabilities
std::map< UUID, double > existence_probabilities
Definition: update_request.h:117
c
void c()
ed::UpdateRequest::poses_removed
std::vector< UUID > poses_removed
Definition: update_request.h:134
ed::PropertyKeyDB::getPropertyKeyDBEntry
const PropertyKeyDBEntry * getPropertyKeyDBEntry(const std::string &name) const
Definition: property_key_db.h:77
ed::UpdateRequest::datas
std::map< UUID, tue::config::DataConstPointer > datas
Definition: update_request.h:146
ed::SearchNode
Definition: world_model.cpp:232
std::set< std::string >
ed::SearchNode::inverse
bool inverse
Definition: world_model.cpp:241
ed::Idx
uint64_t Idx
Definition: types.h:21
ed::EntityPtr
shared_ptr< Entity > EntityPtr
Definition: types.h:35
ed::Property
Definition: property.h:12
ed::WorldModel::addNewEntity
Idx addNewEntity(const EntityConstPtr &e)
Definition: world_model.cpp:463
world_model.h