object_tracker.h
Go to the documentation of this file.
1 #ifndef OBJECT_TRACKER_OBJECT_TRACKER_H
2 #define OBJECT_TRACKER_OBJECT_TRACKER_H
3 
4 #include <ros/ros.h>
5 #include <tf/tf.h>
6 #include <std_msgs/String.h>
7 #include <std_msgs/Float32.h>
9 #include <hector_worldmodel_msgs/SetObjectState.h>
10 #include <hector_worldmodel_msgs/SetObjectName.h>
11 #include <hector_worldmodel_msgs/AddObject.h>
12 #include <hector_worldmodel_msgs/GetObjectModel.h>
13 #include <sensor_msgs/CameraInfo.h>
14 
15 #include <tf/transform_listener.h>
17 
19 
20 #include "ObjectModel.h"
21 
22 namespace hector_object_tracker {
23 
25 public:
26  ObjectTracker();
27  virtual ~ObjectTracker();
28 
29 protected:
30  void sysCommandCb(const std_msgs::StringConstPtr &);
31  void imagePerceptCb(const hector_worldmodel_msgs::ImagePerceptConstPtr &);
32  void posePerceptCb(const hector_worldmodel_msgs::PosePerceptConstPtr &);
33  void objectAgeingCb(const std_msgs::Float32ConstPtr &);
34 
35  void modelUpdateCb(const hector_worldmodel_msgs::ObjectModelConstPtr &);
36 
37  bool setObjectStateCb(hector_worldmodel_msgs::SetObjectState::Request& request, hector_worldmodel_msgs::SetObjectState::Response& response);
38  bool setObjectNameCb(hector_worldmodel_msgs::SetObjectName::Request& request, hector_worldmodel_msgs::SetObjectName::Response& response);
39  bool addObjectCb(hector_worldmodel_msgs::AddObject::Request& request, hector_worldmodel_msgs::AddObject::Response& response);
40  bool getObjectModelCb(hector_worldmodel_msgs::GetObjectModel::Request& request, hector_worldmodel_msgs::GetObjectModel::Response& response);
41 
42  ObjectModel& getModel() { return model; }
43  const ObjectModel& getModel() const { return model; }
44 
46 
48  void publishModel();
49 
50 protected:
51  bool transformPose(const geometry_msgs::Pose& from, geometry_msgs::Pose &to, std_msgs::Header &header, tf::StampedTransform *transform = 0);
52  bool transformPose(const geometry_msgs::PoseWithCovariance& from, geometry_msgs::PoseWithCovariance &to, std_msgs::Header &header);
53  bool mapToNextObstacle(const geometry_msgs::Pose& source, const std_msgs::Header &header, const ObjectInfo &info, geometry_msgs::Pose &mapped);
54 
55 private:
62 
64  std::string class_id;
65  ObjectInfo::_support_type negative_support;
66  ObjectInfo::_support_type min_support;
67  float min_distance;
68  float max_distance;
72  };
74  std::vector<NegativeUpdatePtr> negativeUpdate;
75  void negativeUpdateCallback(const sensor_msgs::CameraInfoConstPtr &, const NegativeUpdatePtr& info);
76 
82 
87 
89 
91 
93 
96  std::map<std::string,CameraModelPtr> cameraModels;
97  ObjectTracker::CameraModelPtr getCameraModel(const std::string& frame_id, const sensor_msgs::CameraInfo& camera_info);
98 
99  struct MergedModelInfo {
100  std::string prefix;
103  };
105  std::vector<MergedModelPtr> merged_models;
106  void mergeModelCallback(const hector_worldmodel_msgs::ObjectModelConstPtr &new_model, const MergedModelPtr& info);
107 
108  std::string _frame_id;
109  std::string _worldmodel_ns;
110 
113 };
114 
115 } // namespace hector_object_tracker
116 
117 #endif // OBJECT_TRACKER_OBJECT_TRACKER_H
bool transformPose(const geometry_msgs::Pose &from, geometry_msgs::Pose &to, std_msgs::Header &header, tf::StampedTransform *transform=0)
void publishModelEvent(const ros::TimerEvent &)
void imagePerceptCb(const hector_worldmodel_msgs::ImagePerceptConstPtr &)
boost::shared_ptr< NegativeUpdateInfo > NegativeUpdatePtr
std::map< std::string, CameraModelPtr > cameraModels
const ObjectModel & getModel() const
bool setObjectNameCb(hector_worldmodel_msgs::SetObjectName::Request &request, hector_worldmodel_msgs::SetObjectName::Response &response)
boost::shared_ptr< MergedModelInfo > MergedModelPtr
std::vector< NegativeUpdatePtr > negativeUpdate
void sysCommandCb(const std_msgs::StringConstPtr &)
std::vector< MergedModelPtr > merged_models
boost::shared_ptr< image_geometry::PinholeCameraModel > CameraModelPtr
void modelUpdateCb(const hector_worldmodel_msgs::ObjectModelConstPtr &)
bool addObjectCb(hector_worldmodel_msgs::AddObject::Request &request, hector_worldmodel_msgs::AddObject::Response &response)
void negativeUpdateCallback(const sensor_msgs::CameraInfoConstPtr &, const NegativeUpdatePtr &info)
void mergeModelCallback(const hector_worldmodel_msgs::ObjectModelConstPtr &new_model, const MergedModelPtr &info)
ObjectTracker::CameraModelPtr getCameraModel(const std::string &frame_id, const sensor_msgs::CameraInfo &camera_info)
bool mapToNextObstacle(const geometry_msgs::Pose &source, const std_msgs::Header &header, const ObjectInfo &info, geometry_msgs::Pose &mapped)
void posePerceptCb(const hector_worldmodel_msgs::PosePerceptConstPtr &)
void objectAgeingCb(const std_msgs::Float32ConstPtr &)
bool setObjectStateCb(hector_worldmodel_msgs::SetObjectState::Request &request, hector_worldmodel_msgs::SetObjectState::Response &response)
bool getObjectModelCb(hector_worldmodel_msgs::GetObjectModel::Request &request, hector_worldmodel_msgs::GetObjectModel::Response &response)


hector_object_tracker
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:35:13