#include <body.h>
Definition at line 57 of file body.h.
◆ Body()
◆ ~Body()
◆ 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()
◆ onCropped()
void Body::onCropped |
( |
sensor_msgs::ImageConstPtr |
roi | ) |
|
|
private |
◆ onRoI()
void Body::onRoI |
( |
hri_msgs::NormalizedRegionOfInterest2DConstPtr |
roi | ) |
|
|
private |
◆ onSkeleton()
void Body::onSkeleton |
( |
hri_msgs::Skeleton2DConstPtr |
skeleton | ) |
|
|
private |
◆ roi()
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()
◆ 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.
◆ _reference_frame
std::string hri::Body::_reference_frame |
|
private |
◆ _tf_buffer_ptr
◆ cropped_
cv::Mat hri::Body::cropped_ |
|
private |
◆ cropped_subscriber_
◆ nb_roi
◆ roi_
◆ roi_subscriber_
◆ skeleton_
◆ skeleton_subscriber_
The documentation for this class was generated from the following files:
NormROI roi() const
If available, returns the normalized 2D region of interest (RoI) of the body.