33 #include <geometry_msgs/TransformStamped.h> 34 #include <sensor_msgs/RegionOfInterest.h> 35 #include <sensor_msgs/Image.h> 36 #include <hri_msgs/Skeleton2D.h> 37 #include <hri_msgs/NormalizedPointOfInterest2D.h> 39 #include <boost/optional.hpp> 44 #include <opencv2/core.hpp> 60 const std::string& reference_frame);
68 return BODY_TF_PREFIX +
id_;
108 std::vector<SkeletonPoint>
skeleton()
const;
112 boost::optional<geometry_msgs::TransformStamped>
transform()
const;
114 void init()
override;
120 void onRoI(sensor_msgs::RegionOfInterestConstPtr roi);
124 void onCropped(sensor_msgs::ImageConstPtr roi);
128 void onSkeleton(hri_msgs::Skeleton2DConstPtr skeleton);
std::vector< SkeletonPoint > skeleton_
hri_msgs::NormalizedPointOfInterest2D SkeletonPoint
std::weak_ptr< Body > BodyWeakPtr
void onRoI(sensor_msgs::RegionOfInterestConstPtr roi)
std::shared_ptr< Body > BodyPtr
std::vector< SkeletonPoint > skeleton() const
Returns the 2D skeleton keypoints.
std::weak_ptr< const Body > BodyWeakConstPtr
Body(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
static const std::string BODY_TF_PREFIX("body_")
void onCropped(sensor_msgs::ImageConstPtr roi)
static const ros::Duration BODY_TF_TIMEOUT(0.01)
ros::Subscriber roi_subscriber_
tf2_ros::Buffer * _tf_buffer_ptr
std::shared_ptr< const Body > BodyConstPtr
std::string _reference_frame
cv::Rect roi() const
If available, returns the 2D region of interest (RoI) of the body.
void onSkeleton(hri_msgs::Skeleton2DConstPtr skeleton)
ros::Subscriber skeleton_subscriber_
std::string frame() const
the name of the tf frame that correspond to this body
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the (stamped) 3D transform of the body (if available).
ros::Subscriber cropped_subscriber_
cv::Mat cropped() const
Returns the body image, cropped from the source image.