#include <geometry_msgs/TransformStamped.h>#include <sensor_msgs/Image.h>#include <hri_msgs/Skeleton2D.h>#include <hri_msgs/NormalizedPointOfInterest2D.h>#include <hri_msgs/NormalizedRegionOfInterest2D.h>#include <memory>#include <boost/optional.hpp>#include "base.h"#include "ros/subscriber.h"#include <opencv2/core.hpp>#include "tf2_ros/transform_listener.h"

Go to the source code of this file.
Classes | |
| class | hri::Body |
Namespaces | |
| hri | |
Typedefs | |
| typedef std::shared_ptr< const Body > | hri::BodyConstPtr |
| typedef std::shared_ptr< Body > | hri::BodyPtr |
| typedef std::weak_ptr< const Body > | hri::BodyWeakConstPtr |
| typedef std::weak_ptr< Body > | hri::BodyWeakPtr |
| typedef hri_msgs::NormalizedRegionOfInterest2D | NormROI |
| typedef hri_msgs::NormalizedPointOfInterest2D | SkeletonPoint |
Functions | |
| const static std::string | hri::BODY_TF_PREFIX ("body_") |
| const static ros::Duration | hri::BODY_TF_TIMEOUT (0.01) |
| typedef hri_msgs::NormalizedPointOfInterest2D SkeletonPoint |