1 #ifndef OBJECT_TRACKER_OBJECT_H 2 #define OBJECT_TRACKER_OBJECT_H 6 #include <visualization_msgs/MarkerArray.h> 9 #include <Eigen/Geometry> 20 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
24 typedef hector_worldmodel_msgs::ObjectState::_state_type
StateType;
26 Object(
const std::string class_id =
"",
const std::string object_id =
"");
27 Object(
const hector_worldmodel_msgs::Object& other);
32 void getMessage(hector_worldmodel_msgs::Object&
object)
const;
33 hector_worldmodel_msgs::Object
getMessage()
const;
37 void setPose(
const geometry_msgs::PoseWithCovariance& pose);
39 void getPose(geometry_msgs::Pose& pose)
const;
41 void setPose(
const geometry_msgs::Pose& pose);
60 return this->
info.class_id;
64 return this->
info.object_id;
68 this->
info.object_id = object_id;
72 return this->
info.support;
76 this->
info.support = support;
80 this->
info.support += support;
84 return this->
state.state;
90 return this->
info.name;
94 this->
info.name = name;
106 return this->
header.stamp;
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);
138 #endif // OBJECT_TRACKER_OBJECT_H void getPose(geometry_msgs::Pose &pose) const
const std::string & getName() const
Eigen::Matrix3f covariance
void setPosition(const Eigen::Vector3f &position)
void update(const tf::Pose &poseB, const Eigen::Matrix3f &covarianceB, float support)
std_msgs::Header getHeader() const
ObjectPtr transform(tf::Transformer &tf, const std::string &target_frame) const
void intersect(const tf::Pose &poseB, const Eigen::Matrix3f &covarianceB, float support)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< Object > Ptr
void setSupport(float support)
const Eigen::Matrix3f & getCovariance() const
boost::shared_ptr< Object const > ConstPtr
const Eigen::Quaternionf & getOrientation() const
Object(const std::string class_id="", const std::string object_id="")
static void setNamespace(const std::string &ns)
const std::string & getClassId() const
void setOrientation(const geometry_msgs::Quaternion &orientation)
void setState(const StateType &state)
hector_worldmodel_msgs::ObjectState::_state_type StateType
const Eigen::Vector3f & getPosition() const
void setName(const std::string &name)
void setObjectId(const std::string &object_id)
hector_worldmodel_msgs::Object getMessage() const
Object & operator=(const hector_worldmodel_msgs::Object &other)
Eigen::Quaternionf orientation
static std::map< std::string, unsigned int > object_count
ros::Time getStamp() const
void setHeader(const std_msgs::Header &header)
void updateOrientation(const tf::Quaternion &orientationB, double slerp_factor)
const std::string & getObjectId() const
void getPoseWithCovariance(geometry_msgs::PoseWithCovariance &pose) const
void getVisualization(visualization_msgs::MarkerArray &markers) const
double getDistance(const Object &other)
static std::string object_namespace
StateType getState() const
void setPose(const geometry_msgs::PoseWithCovariance &pose)
void addSupport(float support)
void setCovariance(const Eigen::Matrix3f &covariance)