Class Body

Inheritance Relationships

Base Types

Class Documentation

class Body : public hri::FeatureTracker, public std::enable_shared_from_this<Body>

Public Functions

Body(ID id, NodeInterfaces node_interfaces, rclcpp::CallbackGroup::SharedPtr callback_group, const tf2::BufferCore &tf_buffer, const std::string &reference_frame)
virtual ~Body()
inline std::optional<cv::Rect2f> roi() const

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

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

inline std::optional<cv::Mat> cropped() const

Returns the body image, cropped from the source image.

inline std::optional<SkeletalKeypoints> 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

inline std::optional<std::string> bodyDescription() const

Returns the body kinematic description in URDF format.

The body kinematic description follows the template defined in http://www.ros.org/reps/rep-0155.html#kinematic-model-of-the-human