37 const std::string& reference_frame)
51 ns_ =
"/humans/bodies/" +
id_;
66 roi_ = cv::Rect(roi->x_offset, roi->y_offset, roi->width, roi->height);
106 <<
". Are the frames published?");
107 return boost::optional<geometry_msgs::TransformStamped>();
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::vector< SkeletonPoint > skeleton_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void onRoI(sensor_msgs::RegionOfInterestConstPtr roi)
std::vector< SkeletonPoint > skeleton() const
Returns the 2D skeleton keypoints.
void onCropped(sensor_msgs::ImageConstPtr roi)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
static const ros::Duration BODY_TF_TIMEOUT(0.01)
ros::Subscriber roi_subscriber_
tf2_ros::Buffer * _tf_buffer_ptr
std::string _reference_frame
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
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.