1 #ifndef OBJECT_TRACKER_OBJECTMODEL_H 2 #define OBJECT_TRACKER_OBJECTMODEL_H 6 #include <std_msgs/String.h> 7 #include <visualization_msgs/MarkerArray.h> 11 #include <boost/thread/recursive_mutex.hpp> 13 #include <Eigen/Geometry> 26 ObjectModel(
const std::string& frame_id = std::string());
37 void getMessage(hector_worldmodel_msgs::ObjectModel& model)
const;
38 hector_worldmodel_msgs::ObjectModelPtr
getMessage()
const;
47 ObjectPtr create(
const std::string& class_id =
"",
const std::string& object_id =
"");
48 ObjectPtr add(
const std::string& class_id =
"",
const std::string& object_id =
"");
51 void remove(iterator it);
60 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;
73 #endif // OBJECT_TRACKER_OBJECTMODEL_H
void getVisualization(visualization_msgs::MarkerArray &markers) const
ObjectModel(const std::string &frame_id=std::string())
std_msgs::Header getHeader() const
void merge(const ObjectPtr &other, tf::TransformListener &tf, const std::string &prefix=std::string())
const_iterator begin() const
hector_worldmodel_msgs::ObjectModelPtr getMessage() const
ObjectList getObjects() const
ObjectList::iterator iterator
std::list< ObjectPtr > ObjectList
boost::recursive_mutex objectsMutex
ObjectList::const_iterator const_iterator
void setFrameId(const std::string &frame_id)
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
const_iterator end() const
ObjectModel & operator=(const ObjectModel &other)
ObjectPtr getObject(const std::string &object_id) const
ObjectPtr add(const std::string &class_id="", const std::string &object_id="")
ObjectPtr create(const std::string &class_id="", const std::string &object_id="")
void mergeWith(const ObjectModel &other, tf::TransformListener &tf, const std::string &prefix=std::string())