ObjectModel.h
Go to the documentation of this file.
00001 #ifndef OBJECT_TRACKER_OBJECTMODEL_H
00002 #define OBJECT_TRACKER_OBJECTMODEL_H
00003 
00004 #include <hector_object_tracker/types.h>
00005 
00006 #include <std_msgs/String.h>
00007 #include <visualization_msgs/MarkerArray.h>
00008 
00009 #include <list>
00010 #include <string>
00011 #include <boost/thread/recursive_mutex.hpp>
00012 
00013 #include <Eigen/Geometry>
00014 
00015 #include <tf/transform_listener.h>
00016 
00017 namespace hector_object_tracker {
00018 
00019 class ObjectModel
00020 {
00021 public:
00022     typedef ObjectList::iterator iterator;
00023     typedef ObjectList::const_iterator const_iterator;
00024 
00025 public:
00026     ObjectModel(const std::string& frame_id = std::string());
00027     ObjectModel(const ObjectModel&);
00028     virtual ~ObjectModel();
00029 
00030     ObjectList getObjects() const;
00031     ObjectList getObjects(const std::string& class_id) const;
00032     ObjectPtr getObject(const std::string& object_id) const;
00033 
00034     std_msgs::Header getHeader() const;
00035     void setFrameId(const std::string &frame_id);
00036 
00037     void getMessage(hector_worldmodel_msgs::ObjectModel& model) const;
00038     hector_worldmodel_msgs::ObjectModelPtr getMessage() const;
00039     void getVisualization(visualization_msgs::MarkerArray &markers) const;
00040     void reset();
00041 
00042     iterator begin() { return objects.begin(); }
00043     iterator end()   { return objects.end(); }
00044     const_iterator begin() const { return objects.begin(); }
00045     const_iterator end() const { return objects.end(); }
00046 
00047     ObjectPtr create(const std::string& class_id = "", const std::string& object_id = "");
00048     ObjectPtr add(const std::string& class_id = "", const std::string& object_id = "");
00049     ObjectPtr add(ObjectPtr object);
00050     void remove(ObjectPtr object);
00051     void remove(iterator it);
00052 
00053     ObjectModel &operator=(const ObjectModel& other);
00054     ObjectModel &operator=(const hector_worldmodel_msgs::ObjectModel& other);
00055 
00056     void lock() const { objectsMutex.lock(); }
00057     bool try_lock() const { return objectsMutex.try_lock(); }
00058     void unlock() const { objectsMutex.unlock(); }
00059 
00060     float getBestCorrespondence(ObjectPtr &object, const tf::Pose& pose, const Eigen::Matrix3f& covariance, const std::string& class_id, const std::string& name, float max_distance = 0.0) const;
00061 
00062     void mergeWith(const ObjectModel& other, tf::TransformListener& tf, const std::string& prefix = std::string());
00063     void merge(const ObjectPtr& other, tf::TransformListener& tf, const std::string& prefix = std::string());
00064 
00065 private:
00066     std_msgs::Header header;
00067     ObjectList objects;
00068     mutable boost::recursive_mutex objectsMutex;
00069 };
00070 
00071 } // namespace hector_object_tracker
00072 
00073 #endif // OBJECT_TRACKER_OBJECTMODEL_H


hector_object_tracker
Author(s): Johannes Meyer
autogenerated on Thu Jun 6 2019 20:20:14