$search
00001 #include "ObjectModel.h" 00002 #include "Object.h" 00003 00004 namespace object_tracker { 00005 00006 ObjectModel::ObjectModel() 00007 {} 00008 00009 ObjectModel::~ObjectModel() 00010 {} 00011 00012 ObjectModel::ObjectList ObjectModel::getObjects() const 00013 { 00014 boost::recursive_mutex::scoped_lock lock(objectsMutex); 00015 return objects; 00016 } 00017 00018 ObjectModel::ObjectList ObjectModel::getObjects(const std::string& class_id) const 00019 { 00020 boost::recursive_mutex::scoped_lock lock(objectsMutex); 00021 ObjectList class_list; 00022 00023 for(const_iterator it = begin(); it != end(); ++it) { 00024 if ((*it)->getClassId() == class_id) class_list.push_back(*it); 00025 } 00026 00027 return class_list; 00028 } 00029 00030 ObjectPtr ObjectModel::getObject(const std::string& object_id) const { 00031 boost::recursive_mutex::scoped_lock lock(objectsMutex); 00032 00033 for(const_iterator it = begin(); it != end(); ++it) { 00034 if ((*it)->getObjectId() == object_id) return *it; 00035 } 00036 00037 return ObjectPtr(); 00038 } 00039 00040 worldmodel_msgs::ObjectModelPtr ObjectModel::getObjectModelMessage() const { 00041 boost::recursive_mutex::scoped_lock lock(objectsMutex); 00042 worldmodel_msgs::ObjectModelPtr model(new worldmodel_msgs::ObjectModel()); 00043 00044 model->objects.reserve(objects.size()); 00045 for(ObjectList::const_iterator it = objects.begin(); it != objects.end(); ++it) 00046 model->objects.push_back((*it)->getObjectMessage()); 00047 00048 return model; 00049 } 00050 00051 void ObjectModel::reset() 00052 { 00053 boost::recursive_mutex::scoped_lock lock(objectsMutex); 00054 objects.clear(); 00055 Object::reset(); 00056 } 00057 00058 ObjectPtr ObjectModel::add(const std::string& class_id, const std::string& object_id) { 00059 return add(ObjectPtr(new Object(class_id, object_id))); 00060 } 00061 00062 ObjectPtr ObjectModel::add(ObjectPtr object) { 00063 objects.push_back(object); 00064 return object; 00065 } 00066 00067 void ObjectModel::remove(ObjectPtr object) { 00068 for(ObjectList::iterator it = objects.begin(); it != objects.end(); ++it) { 00069 if (*it == object) { 00070 remove(it); 00071 return; 00072 } 00073 } 00074 } 00075 00076 void ObjectModel::remove(iterator it) { 00077 objects.erase(it); 00078 } 00079 00080 void ObjectModel::getVisualization(visualization_msgs::MarkerArray &markers) const { 00081 boost::recursive_mutex::scoped_lock lock(objectsMutex); 00082 00083 markers.markers.clear(); 00084 for(ObjectList::const_iterator it = objects.begin(); it != objects.end(); ++it) { 00085 (*it)->getVisualization(markers); 00086 } 00087 } 00088 00089 } // namespace object_tracker