Go to the documentation of this file.00001 #ifndef OBJECT_TRACKER_OBJECT_H
00002 #define OBJECT_TRACKER_OBJECT_H
00003
00004 #include <hector_object_tracker/types.h>
00005
00006 #include <visualization_msgs/MarkerArray.h>
00007 #include <tf/transform_listener.h>
00008
00009 #include <Eigen/Geometry>
00010
00011 #include <ros/ros.h>
00012
00013 #include <map>
00014
00015 namespace hector_object_tracker {
00016
00017 class Object
00018 {
00019 public:
00020 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00021
00022 typedef boost::shared_ptr<Object> Ptr;
00023 typedef boost::shared_ptr<Object const> ConstPtr;
00024 typedef hector_worldmodel_msgs::ObjectState::_state_type StateType;
00025
00026 Object(const std::string class_id = "", const std::string object_id = "");
00027 Object(const hector_worldmodel_msgs::Object& other);
00028 virtual ~Object();
00029
00030 static void reset();
00031
00032 void getMessage(hector_worldmodel_msgs::Object& object) const;
00033 hector_worldmodel_msgs::Object getMessage() const;
00034 void getVisualization(visualization_msgs::MarkerArray &markers) const;
00035
00036 void getPoseWithCovariance(geometry_msgs::PoseWithCovariance& pose) const;
00037 void setPose(const geometry_msgs::PoseWithCovariance& pose);
00038
00039 void getPose(geometry_msgs::Pose& pose) const;
00040 void getPose(tf::Pose& pose) const;
00041 void setPose(const geometry_msgs::Pose& pose);
00042 void setPose(const tf::Pose& pose);
00043
00044 const Eigen::Vector3f& getPosition() const;
00045 void setPosition(const Eigen::Vector3f& position);
00046 void setPosition(const geometry_msgs::Point& position);
00047 void setPosition(const tf::Point& point);
00048
00049 const Eigen::Quaternionf& getOrientation() const;
00050 void setOrientation(const geometry_msgs::Quaternion& orientation);
00051 void setOrientation(const tf::Quaternion& orientation);
00052
00053 const Eigen::Matrix3f& getCovariance() const;
00054 void getCovariance(geometry_msgs::PoseWithCovariance::_covariance_type& covariance) const;
00055 void setCovariance(const Eigen::Matrix3f& covariance);
00056 void setCovariance(const tf::Matrix3x3& covariance);
00057 void setCovariance(const geometry_msgs::PoseWithCovariance::_covariance_type& covariance);
00058
00059 const std::string& getClassId() const {
00060 return this->info.class_id;
00061 }
00062
00063 const std::string& getObjectId() const {
00064 return this->info.object_id;
00065 }
00066
00067 void setObjectId(const std::string& object_id) {
00068 this->info.object_id = object_id;
00069 }
00070
00071 float getSupport() const {
00072 return this->info.support;
00073 }
00074
00075 void setSupport(float support) {
00076 this->info.support = support;
00077 }
00078
00079 void addSupport(float support) {
00080 this->info.support += support;
00081 }
00082
00083 StateType getState() const {
00084 return this->state.state;
00085 }
00086
00087 void setState(const StateType& state);
00088
00089 const std::string& getName() const {
00090 return this->info.name;
00091 }
00092
00093 void setName(const std::string& name) {
00094 this->info.name = name;
00095 }
00096
00097 std_msgs::Header getHeader() const {
00098 return this->header;
00099 }
00100
00101 void setHeader(const std_msgs::Header &header) {
00102 this->header = header;
00103 }
00104
00105 ros::Time getStamp() const {
00106 return this->header.stamp;
00107 }
00108
00109 void intersect(const tf::Pose& poseB, const Eigen::Matrix3f& covarianceB, float support);
00110 void update(const tf::Pose& poseB, const Eigen::Matrix3f& covarianceB, float support);
00111 void updateOrientation(const tf::Quaternion& orientationB, double slerp_factor);
00112
00113 static void setNamespace(const std::string& ns);
00114
00115 Object& operator=(const hector_worldmodel_msgs::Object& other);
00116
00117 ObjectPtr transform(tf::Transformer& tf, const std::string& target_frame) const;
00118 ObjectPtr transform(tf::Transformer& tf, const std::string& target_frame, const ros::Time& target_time) const;
00119
00120 double getDistance(const Object &other);
00121
00122 private:
00123 ros::NodeHandle nh;
00124 std_msgs::Header header;
00125 ObjectInfo info;
00126 ObjectState state;
00127
00128 Eigen::Vector3f position;
00129 Eigen::Quaternionf orientation;
00130 Eigen::Matrix3f covariance;
00131
00132 static std::map<std::string,unsigned int> object_count;
00133 static std::string object_namespace;
00134 };
00135
00136 }
00137
00138 #endif // OBJECT_TRACKER_OBJECT_H