Object.h
Go to the documentation of this file.
1 #ifndef OBJECT_TRACKER_OBJECT_H
2 #define OBJECT_TRACKER_OBJECT_H
3 
5 
6 #include <visualization_msgs/MarkerArray.h>
8 
9 #include <Eigen/Geometry>
10 
11 #include <ros/ros.h>
12 
13 #include <map>
14 
15 namespace hector_object_tracker {
16 
17 class Object
18 {
19 public:
20  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
21 
24  typedef hector_worldmodel_msgs::ObjectState::_state_type StateType;
25 
26  Object(const std::string class_id = "", const std::string object_id = "");
27  Object(const hector_worldmodel_msgs::Object& other);
28  virtual ~Object();
29 
30  static void reset();
31 
32  void getMessage(hector_worldmodel_msgs::Object& object) const;
33  hector_worldmodel_msgs::Object getMessage() const;
34  void getVisualization(visualization_msgs::MarkerArray &markers) const;
35 
36  void getPoseWithCovariance(geometry_msgs::PoseWithCovariance& pose) const;
37  void setPose(const geometry_msgs::PoseWithCovariance& pose);
38 
39  void getPose(geometry_msgs::Pose& pose) const;
40  void getPose(tf::Pose& pose) const;
41  void setPose(const geometry_msgs::Pose& pose);
42  void setPose(const tf::Pose& pose);
43 
44  const Eigen::Vector3f& getPosition() const;
45  void setPosition(const Eigen::Vector3f& position);
46  void setPosition(const geometry_msgs::Point& position);
47  void setPosition(const tf::Point& point);
48 
49  const Eigen::Quaternionf& getOrientation() const;
50  void setOrientation(const geometry_msgs::Quaternion& orientation);
52 
53  const Eigen::Matrix3f& getCovariance() const;
54  void getCovariance(geometry_msgs::PoseWithCovariance::_covariance_type& covariance) const;
55  void setCovariance(const Eigen::Matrix3f& covariance);
57  void setCovariance(const geometry_msgs::PoseWithCovariance::_covariance_type& covariance);
58 
59  const std::string& getClassId() const {
60  return this->info.class_id;
61  }
62 
63  const std::string& getObjectId() const {
64  return this->info.object_id;
65  }
66 
67  void setObjectId(const std::string& object_id) {
68  this->info.object_id = object_id;
69  }
70 
71  float getSupport() const {
72  return this->info.support;
73  }
74 
75  void setSupport(float support) {
76  this->info.support = support;
77  }
78 
79  void addSupport(float support) {
80  this->info.support += support;
81  }
82 
83  StateType getState() const {
84  return this->state.state;
85  }
86 
87  void setState(const StateType& state);
88 
89  const std::string& getName() const {
90  return this->info.name;
91  }
92 
93  void setName(const std::string& name) {
94  this->info.name = name;
95  }
96 
97  std_msgs::Header getHeader() const {
98  return this->header;
99  }
100 
101  void setHeader(const std_msgs::Header &header) {
102  this->header = header;
103  }
104 
105  ros::Time getStamp() const {
106  return this->header.stamp;
107  }
108 
109  void intersect(const tf::Pose& poseB, const Eigen::Matrix3f& covarianceB, float support);
110  void update(const tf::Pose& poseB, const Eigen::Matrix3f& covarianceB, float support);
111  void updateOrientation(const tf::Quaternion& orientationB, double slerp_factor);
112 
113  static void setNamespace(const std::string& ns);
114 
115  Object& operator=(const hector_worldmodel_msgs::Object& other);
116 
117  ObjectPtr transform(tf::Transformer& tf, const std::string& target_frame) const;
118  ObjectPtr transform(tf::Transformer& tf, const std::string& target_frame, const ros::Time& target_time) const;
119 
120  double getDistance(const Object &other);
121 
122 private:
124  std_msgs::Header header;
125  ObjectInfo info;
126  ObjectState state;
127 
128  Eigen::Vector3f position;
129  Eigen::Quaternionf orientation;
130  Eigen::Matrix3f covariance;
131 
132  static std::map<std::string,unsigned int> object_count;
133  static std::string object_namespace;
134 };
135 
136 } // namespace hector_object_tracker
137 
138 #endif // OBJECT_TRACKER_OBJECT_H
void getPose(geometry_msgs::Pose &pose) const
Definition: Object.cpp:64
std_msgs::Header header
Definition: Object.h:124
const std::string & getName() const
Definition: Object.h:89
Eigen::Matrix3f covariance
Definition: Object.h:130
void setPosition(const Eigen::Vector3f &position)
Definition: Object.cpp:99
void update(const tf::Pose &poseB, const Eigen::Matrix3f &covarianceB, float support)
Definition: Object.cpp:185
std_msgs::Header getHeader() const
Definition: Object.h:97
ObjectPtr transform(tf::Transformer &tf, const std::string &target_frame) const
Definition: Object.cpp:288
Eigen::Vector3f position
Definition: Object.h:128
float getSupport() const
Definition: Object.h:71
void intersect(const tf::Pose &poseB, const Eigen::Matrix3f &covarianceB, float support)
Definition: Object.cpp:165
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< Object > Ptr
Definition: Object.h:22
void setSupport(float support)
Definition: Object.h:75
const Eigen::Matrix3f & getCovariance() const
Definition: Object.cpp:127
boost::shared_ptr< Object const > ConstPtr
Definition: Object.h:23
const Eigen::Quaternionf & getOrientation() const
Definition: Object.cpp:112
Object(const std::string class_id="", const std::string object_id="")
Definition: Object.cpp:13
ros::NodeHandle nh
Definition: Object.h:123
static void setNamespace(const std::string &ns)
Definition: Object.cpp:276
const std::string & getClassId() const
Definition: Object.h:59
void setOrientation(const geometry_msgs::Quaternion &orientation)
Definition: Object.cpp:117
void setState(const StateType &state)
Definition: Object.cpp:159
hector_worldmodel_msgs::ObjectState::_state_type StateType
Definition: Object.h:24
const Eigen::Vector3f & getPosition() const
Definition: Object.cpp:95
void setName(const std::string &name)
Definition: Object.h:93
void setObjectId(const std::string &object_id)
Definition: Object.h:67
hector_worldmodel_msgs::Object getMessage() const
Definition: Object.cpp:48
Object & operator=(const hector_worldmodel_msgs::Object &other)
Definition: Object.cpp:280
Eigen::Quaternionf orientation
Definition: Object.h:129
static std::map< std::string, unsigned int > object_count
Definition: Object.h:132
ros::Time getStamp() const
Definition: Object.h:105
void setHeader(const std_msgs::Header &header)
Definition: Object.h:101
void updateOrientation(const tf::Quaternion &orientationB, double slerp_factor)
Definition: Object.cpp:204
const std::string & getObjectId() const
Definition: Object.h:63
void getPoseWithCovariance(geometry_msgs::PoseWithCovariance &pose) const
Definition: Object.cpp:54
void getVisualization(visualization_msgs::MarkerArray &markers) const
Definition: Object.cpp:217
double getDistance(const Object &other)
Definition: Object.cpp:320
static std::string object_namespace
Definition: Object.h:133
StateType getState() const
Definition: Object.h:83
void setPose(const geometry_msgs::PoseWithCovariance &pose)
Definition: Object.cpp:59
void addSupport(float support)
Definition: Object.h:79
void setCovariance(const Eigen::Matrix3f &covariance)
Definition: Object.cpp:143


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