#include <hri_msgs/NormalizedPointOfInterest2D.h>#include <hri_msgs/NormalizedRegionOfInterest2D.h>#include <hri_msgs/FacialLandmarks.h>#include <hri_msgs/SoftBiometrics.h>#include <sensor_msgs/Image.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::Face |
| struct | hri::IntensityConfidence |
Namespaces | |
| hri | |
Typedefs | |
| typedef std::shared_ptr< const Face > | hri::FaceConstPtr |
| typedef std::shared_ptr< Face > | hri::FacePtr |
| typedef std::weak_ptr< const Face > | hri::FaceWeakConstPtr |
| typedef std::weak_ptr< Face > | hri::FaceWeakPtr |
| typedef hri_msgs::NormalizedRegionOfInterest2D | NormROI |
Enumerations | |
| enum | hri::Gender { hri::FEMALE = 1, hri::MALE = 2, hri::OTHER = 3 } |
Functions | |
| const static std::string | hri::FACE_TF_PREFIX ("face_") |
| const static ros::Duration | hri::FACE_TF_TIMEOUT (0.01) |
| const static std::string | hri::GAZE_TF_PREFIX ("gaze_") |