Public Member Functions | Private Member Functions | Private Attributes | List of all members
hri::Body Class Reference

#include <body.h>

Inheritance diagram for hri::Body:
Inheritance graph
[legend]

Public Member Functions

 Body (ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
 
cv::Mat cropped () const
 Returns the body image, cropped from the source image. More...
 
std::string frame () const
 the name of the tf frame that correspond to this body More...
 
void init () override
 
NormROI roi () const
 If available, returns the normalized 2D region of interest (RoI) of the body. More...
 
std::vector< SkeletonPointskeleton () const
 Returns the 2D skeleton keypoints. More...
 
boost::optional< geometry_msgs::TransformStamped > transform () const
 Returns the (stamped) 3D transform of the body (if available). More...
 
virtual ~Body ()
 
- Public Member Functions inherited from hri::FeatureTracker
 FeatureTracker (const FeatureTracker &)=delete
 
 FeatureTracker (ID id, const ros::NodeHandle &nh)
 
std::string getNamespace () const
 
ID id () const
 
std::string ns () const
 
bool operator< (const FeatureTracker &other) const
 
virtual ~FeatureTracker ()
 

Private Member Functions

void onCropped (sensor_msgs::ImageConstPtr roi)
 
void onRoI (hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
 
void onSkeleton (hri_msgs::Skeleton2DConstPtr skeleton)
 

Private Attributes

std::string _reference_frame
 
tf2_ros::Buffer_tf_buffer_ptr
 
cv::Mat cropped_
 
ros::Subscriber cropped_subscriber_
 
size_t nb_roi
 
NormROI roi_
 
ros::Subscriber roi_subscriber_
 
std::vector< SkeletonPointskeleton_
 
ros::Subscriber skeleton_subscriber_
 

Additional Inherited Members

- Protected Attributes inherited from hri::FeatureTracker
ID id_
 
ros::NodeHandle node_
 
std::string ns_
 

Detailed Description

Definition at line 57 of file body.h.

Constructor & Destructor Documentation

◆ Body()

Body::Body ( ID  id,
ros::NodeHandle nh,
tf2_ros::Buffer tf_buffer_ptr,
const std::string &  reference_frame 
)

Definition at line 36 of file body.cpp.

◆ ~Body()

Body::~Body ( )
virtual

Definition at line 43 of file body.cpp.

Member Function Documentation

◆ cropped()

cv::Mat Body::cropped ( ) const

Returns the body image, cropped from the source image.

Definition at line 79 of file body.cpp.

◆ frame()

std::string hri::Body::frame ( ) const
inline

the name of the tf frame that correspond to this body

Definition at line 67 of file body.h.

◆ init()

void Body::init ( )
overridevirtual

Implements hri::FeatureTracker.

Definition at line 49 of file body.cpp.

◆ onCropped()

void Body::onCropped ( sensor_msgs::ImageConstPtr  roi)
private

Definition at line 74 of file body.cpp.

◆ onRoI()

void Body::onRoI ( hri_msgs::NormalizedRegionOfInterest2DConstPtr  roi)
private

Definition at line 64 of file body.cpp.

◆ onSkeleton()

void Body::onSkeleton ( hri_msgs::Skeleton2DConstPtr  skeleton)
private

Definition at line 84 of file body.cpp.

◆ roi()

NormROI Body::roi ( ) const

If available, returns the normalized 2D region of interest (RoI) of the body.

Use example:

HRIListener hri_listener;
auto bodies = hri_listener.getBodies();
for (auto const& body : bodies)
{
auto roi = body.second.lock()->roi();
cout << "Normalized size of body_" << body.first << ": ";
cout << (roi.xmax - roi.xmin) << "x" << (roi.ymax - roi.ymin) << endl;
}

The coordinates are provided in the original camera's image coordinate space.

The header's timestamp is the same as a the timestamp of the original image from which the body has been detected.

Definition at line 69 of file body.cpp.

◆ skeleton()

std::vector< SkeletonPoint > Body::skeleton ( ) const

Returns the 2D skeleton keypoints.

Points coordinates are in the image space of the source image, and normalised between 0.0 and 1.0.

The skeleton joints indices follow those defined in http://docs.ros.org/en/api/hri_msgs/html/msg/Skeleton2D.html

Definition at line 89 of file body.cpp.

◆ transform()

boost::optional< geometry_msgs::TransformStamped > Body::transform ( ) const

Returns the (stamped) 3D transform of the body (if available).

Definition at line 94 of file body.cpp.

Member Data Documentation

◆ _reference_frame

std::string hri::Body::_reference_frame
private

Definition at line 132 of file body.h.

◆ _tf_buffer_ptr

tf2_ros::Buffer* hri::Body::_tf_buffer_ptr
private

Definition at line 133 of file body.h.

◆ cropped_

cv::Mat hri::Body::cropped_
private

Definition at line 126 of file body.h.

◆ cropped_subscriber_

ros::Subscriber hri::Body::cropped_subscriber_
private

Definition at line 124 of file body.h.

◆ nb_roi

size_t hri::Body::nb_roi
private

Definition at line 118 of file body.h.

◆ roi_

NormROI hri::Body::roi_
private

Definition at line 122 of file body.h.

◆ roi_subscriber_

ros::Subscriber hri::Body::roi_subscriber_
private

Definition at line 120 of file body.h.

◆ skeleton_

std::vector<SkeletonPoint> hri::Body::skeleton_
private

Definition at line 130 of file body.h.

◆ skeleton_subscriber_

ros::Subscriber hri::Body::skeleton_subscriber_
private

Definition at line 128 of file body.h.


The documentation for this class was generated from the following files:
hri::body
@ body
Definition: base.h:48
hri::Body::roi
NormROI roi() const
If available, returns the normalized 2D region of interest (RoI) of the body.
Definition: body.cpp:69


libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58