Go to the documentation of this file.
33 #include <hri_msgs/NormalizedPointOfInterest2D.h>
34 #include <hri_msgs/NormalizedRegionOfInterest2D.h>
35 #include <hri_msgs/FacialLandmarks.h>
36 #include <hri_msgs/SoftBiometrics.h>
37 #include <sensor_msgs/Image.h>
39 #include <boost/optional.hpp>
44 #include <opencv2/core.hpp>
48 typedef hri_msgs::NormalizedRegionOfInterest2D
NormROI;
74 const std::string& reference_frame);
136 boost::optional<std::array<hri_msgs::NormalizedPointOfInterest2D, 70>>
facialLandmarks()
const
161 boost::optional<float>
age()
const;
166 boost::optional<Gender>
gender()
const;
170 boost::optional<geometry_msgs::TransformStamped>
transform()
const;
174 boost::optional<geometry_msgs::TransformStamped>
gazeTransform()
const;
176 void init()
override;
182 void onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr
roi);
194 void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks);
std::string frame() const
the name of the tf frame that correspond to this face
hri_msgs::SoftBiometricsConstPtr softbiometrics_
std::string gazeFrame() const
the name of the tf frame that correspond to the gaze direction and orientation of the face
std::shared_ptr< const Face > FaceConstPtr
hri_msgs::NormalizedRegionOfInterest2D NormROI
cv::Mat aligned() const
Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width a...
boost::optional< std::array< IntensityConfidence, 99 > > facialActionUnits() const
the list of the facial action units detected on the face.
Face(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
hri_msgs::NormalizedRegionOfInterest2D NormROI
void onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics)
ros::Subscriber cropped_subscriber_
void onAligned(sensor_msgs::ImageConstPtr roi)
void onCropped(sensor_msgs::ImageConstPtr roi)
ros::Subscriber aligned_subscriber_
const static std::string FACE_TF_PREFIX("face_")
std::weak_ptr< const Face > FaceWeakConstPtr
ros::Subscriber roi_subscriber_
ros::Subscriber landmarks_subscriber_
std::string _reference_frame
void onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
boost::optional< std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > > facialLandmarks() const
the list of the 66 facial landmarks (2D points, expressed in normalised coordinates).
boost::optional< geometry_msgs::TransformStamped > gazeTransform() const
Returns the (stamped) 3D transform of the gaze (if available).
std::weak_ptr< Face > FaceWeakPtr
tf2_ros::Buffer * _tf_buffer_ptr
std::shared_ptr< Face > FacePtr
cv::Mat cropped() const
Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width a...
const static std::string GAZE_TF_PREFIX("gaze_")
std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > facial_landmarks_
boost::optional< float > age() const
ros::Subscriber softbiometrics_subscriber_
const static ros::Duration FACE_TF_TIMEOUT(0.01)
void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks)
NormROI roi() const
Returns the normalized 2D region of interest (RoI) of the face.
boost::optional< Gender > gender() const
std::array< IntensityConfidence, 99 > facial_action_units_
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the (stamped) 3D transform of the face (if available).
libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58