$search
00001 #ifndef OBJECT_TRACKER_OBJECT_H 00002 #define OBJECT_TRACKER_OBJECT_H 00003 00004 #include <boost/shared_ptr.hpp> 00005 #include <worldmodel_msgs/Object.h> 00006 #include <visualization_msgs/MarkerArray.h> 00007 00008 #include <Eigen/Geometry> 00009 00010 #include <ros/ros.h> 00011 00012 #include <map> 00013 00014 namespace object_tracker { 00015 00016 class Object 00017 { 00018 public: 00019 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00020 00021 typedef boost::shared_ptr<Object> Ptr; 00022 typedef boost::shared_ptr<Object const> ConstPtr; 00023 typedef worldmodel_msgs::ObjectState::_state_type State; 00024 00025 Object(const std::string class_id = "", const std::string object_id = ""); 00026 virtual ~Object(); 00027 00028 static void reset(); 00029 00030 const worldmodel_msgs::Object& getObjectMessage() const { 00031 return object; 00032 } 00033 00034 void getVisualization(visualization_msgs::MarkerArray &markers) const; 00035 00036 const geometry_msgs::PoseWithCovariance& getPoseWithCovariance() const { return object.pose; } 00037 void setPose(const geometry_msgs::PoseWithCovariance& pose) { object.pose = pose; } 00038 00039 const geometry_msgs::Pose& getPose() const { return object.pose.pose; } 00040 void setPose(const geometry_msgs::Pose& pose) { object.pose.pose = pose; } 00041 00042 void setPosition(const geometry_msgs::Point& position) { object.pose.pose.position = position; } 00043 void setOrientation(const geometry_msgs::Quaternion& orientation) { object.pose.pose.orientation = orientation; } 00044 00045 const Eigen::Vector3f& getPosition() const; 00046 void setPosition(const Eigen::Vector3f& position); 00047 00048 const Eigen::Matrix3f& getCovariance() const; 00049 void setCovariance(const Eigen::Matrix3f& covariance); 00050 00051 const std::string& getClassId() const { 00052 return object.info.class_id; 00053 } 00054 00055 const std::string& getObjectId() const { 00056 return object.info.object_id; 00057 } 00058 00059 float getSupport() const { 00060 return object.info.support; 00061 } 00062 00063 void setSupport(float support) { 00064 object.info.support = support; 00065 } 00066 00067 void addSupport(float support) { 00068 object.info.support += support; 00069 } 00070 00071 State getState() const { 00072 return object.state.state; 00073 } 00074 00075 void setState(const State& state) { 00076 object.state.state = state; 00077 } 00078 00079 const std::string& getName() const { 00080 return object.info.name; 00081 } 00082 00083 void setName(const std::string& name) { 00084 object.info.name = name; 00085 } 00086 00087 std_msgs::Header getHeader() const { 00088 return object.header; 00089 } 00090 00091 void setHeader(const std_msgs::Header &header) { 00092 object.header = header; 00093 } 00094 00095 void intersect(const Eigen::Vector3f& position, const Eigen::Matrix3f& covariance, float support); 00096 void update(const Eigen::Vector3f& position, const Eigen::Matrix3f& covariance, float support); 00097 00098 static void setNamespace(const std::string& ns); 00099 00100 private: 00101 ros::NodeHandle nh; 00102 worldmodel_msgs::Object object; 00103 00104 Eigen::Vector3f position; 00105 Eigen::Matrix3f covariance; 00106 00107 static std::map<std::string,unsigned int> object_count; 00108 static std::string object_namespace; 00109 }; 00110 00111 typedef Object::Ptr ObjectPtr; 00112 typedef Object::ConstPtr ObjectConstPtr; 00113 typedef Object::State ObjectState; 00114 00115 } // namespace object_tracker 00116 00117 #endif // OBJECT_TRACKER_OBJECT_H