std::vector< SkeletonPoint > skeleton_
hri_msgs::NormalizedRegionOfInterest2D NormROI
std::vector< SkeletonPoint > skeleton() const
Returns the 2D skeleton keypoints.
std::string _reference_frame
tf2_ros::Buffer * _tf_buffer_ptr
void onCropped(sensor_msgs::ImageConstPtr roi)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber skeleton_subscriber_
ros::Subscriber roi_subscriber_
NormROI roi() const
If available, returns the normalized 2D region of interest (RoI) of the body.
void onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the (stamped) 3D transform of the body (if available).
std::string frame() const
the name of the tf frame that correspond to this body
void onSkeleton(hri_msgs::Skeleton2DConstPtr skeleton)
ros::Subscriber cropped_subscriber_
cv::Mat cropped() const
Returns the body image, cropped from the source image.
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const