Public Member Functions | Private Member Functions | Private Attributes | List of all members
hri::Face Class Reference

#include <face.h>

Inheritance diagram for hri::Face:
Inheritance graph
[legend]

Public Member Functions

boost::optional< float > age () const
 
cv::Mat aligned () const
 Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width and /humans/faces/height ROS parameters. More...
 
cv::Mat cropped () const
 Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width and /humans/faces/height ROS parameters. More...
 
 Face (ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
 
boost::optional< std::array< IntensityConfidence, 99 > > facialActionUnits () const
 the list of the facial action units detected on the face. More...
 
boost::optional< std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > > facialLandmarks () const
 the list of the 66 facial landmarks (2D points, expressed in normalised coordinates). More...
 
std::string frame () const
 the name of the tf frame that correspond to this face More...
 
std::string gazeFrame () const
 the name of the tf frame that correspond to the gaze direction and orientation of the face More...
 
boost::optional< geometry_msgs::TransformStamped > gazeTransform () const
 Returns the (stamped) 3D transform of the gaze (if available). More...
 
boost::optional< Gendergender () const
 
void init () override
 
NormROI roi () const
 Returns the normalized 2D region of interest (RoI) of the face. More...
 
boost::optional< geometry_msgs::TransformStamped > transform () const
 Returns the (stamped) 3D transform of the face (if available). More...
 
virtual ~Face ()
 
- Public Member Functions inherited from hri::FeatureTracker
 FeatureTracker (const FeatureTracker &)=delete
 
 FeatureTracker (ID id, const ros::NodeHandle &nh)
 
std::string getNamespace () const
 
ID id () const
 
std::string ns () const
 
bool operator< (const FeatureTracker &other) const
 
virtual ~FeatureTracker ()
 

Private Member Functions

void onAligned (sensor_msgs::ImageConstPtr roi)
 
void onCropped (sensor_msgs::ImageConstPtr roi)
 
void onLandmarks (hri_msgs::FacialLandmarksConstPtr landmarks)
 
void onRoI (hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
 
void onSoftBiometrics (hri_msgs::SoftBiometricsConstPtr biometrics)
 

Private Attributes

std::string _reference_frame
 
tf2_ros::Buffer_tf_buffer_ptr
 
cv::Mat aligned_
 
ros::Subscriber aligned_subscriber_
 
cv::Mat cropped_
 
ros::Subscriber cropped_subscriber_
 
std::array< IntensityConfidence, 99 > facial_action_units_
 
std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > facial_landmarks_
 
ros::Subscriber landmarks_subscriber_
 
size_t nb_roi
 
NormROI roi_
 
ros::Subscriber roi_subscriber_
 
hri_msgs::SoftBiometricsConstPtr softbiometrics_
 
ros::Subscriber softbiometrics_subscriber_
 

Additional Inherited Members

- Protected Attributes inherited from hri::FeatureTracker
ID id_
 
ros::NodeHandle node_
 
std::string ns_
 

Detailed Description

Definition at line 70 of file face.h.

Constructor & Destructor Documentation

◆ Face()

Face::Face ( ID  id,
ros::NodeHandle nh,
tf2_ros::Buffer tf_buffer_ptr,
const std::string &  reference_frame 
)

Definition at line 37 of file face.cpp.

◆ ~Face()

Face::~Face ( )
virtual

Definition at line 46 of file face.cpp.

Member Function Documentation

◆ age()

boost::optional< float > Face::age ( ) const

Definition at line 122 of file face.cpp.

◆ aligned()

cv::Mat Face::aligned ( ) const

Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width and /humans/faces/height ROS parameters.

In addition, the face is rotated so that the eyes are horizontal.

Definition at line 98 of file face.cpp.

◆ cropped()

cv::Mat Face::cropped ( ) const

Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width and /humans/faces/height ROS parameters.

Definition at line 88 of file face.cpp.

◆ facialActionUnits()

boost::optional<std::array<IntensityConfidence, 99> > hri::Face::facialActionUnits ( ) const
inline

the list of the facial action units detected on the face.

Action units indices follow the Action Unit naming convention by Ekman. List here: https://en.wikipedia.org/wiki/Facial_Action_Coding_System

Note that the list is sparse (some indices do not exist in Ekman classification). In addition, depending on the AU detector, some action units might not be detected. In these cases, the confidence value will be 0.

Constants defined in hri_msgs/FacialActionUnits.h can be used to access specific action units by name.

Definition at line 153 of file face.h.

◆ facialLandmarks()

boost::optional<std::array<hri_msgs::NormalizedPointOfInterest2D, 70> > hri::Face::facialLandmarks ( ) const
inline

the list of the 66 facial landmarks (2D points, expressed in normalised coordinates).

The location of the landmarks is defined here: https://github.com/CMU-Perceptual-Computing-Lab/openpose/blob/master/doc/output.md#face-output-format

Constants defined in hri_msgs/FacialLandmarks.h can be used to access specific points on the face.

Definition at line 136 of file face.h.

◆ frame()

std::string hri::Face::frame ( ) const
inline

the name of the tf frame that correspond to this face

Definition at line 80 of file face.h.

◆ gazeFrame()

std::string hri::Face::gazeFrame ( ) const
inline

the name of the tf frame that correspond to the gaze direction and orientation of the face

Definition at line 88 of file face.h.

◆ gazeTransform()

boost::optional< geometry_msgs::TransformStamped > Face::gazeTransform ( ) const

Returns the (stamped) 3D transform of the gaze (if available).

Definition at line 157 of file face.cpp.

◆ gender()

boost::optional< Gender > Face::gender ( ) const

Definition at line 130 of file face.cpp.

◆ init()

void Face::init ( )
overridevirtual

Implements hri::FeatureTracker.

Definition at line 52 of file face.cpp.

◆ onAligned()

void Face::onAligned ( sensor_msgs::ImageConstPtr  roi)
private

Definition at line 93 of file face.cpp.

◆ onCropped()

void Face::onCropped ( sensor_msgs::ImageConstPtr  roi)
private

Definition at line 83 of file face.cpp.

◆ onLandmarks()

void Face::onLandmarks ( hri_msgs::FacialLandmarksConstPtr  landmarks)
private

Definition at line 103 of file face.cpp.

◆ onRoI()

void Face::onRoI ( hri_msgs::NormalizedRegionOfInterest2DConstPtr  roi)
private

Definition at line 73 of file face.cpp.

◆ onSoftBiometrics()

void Face::onSoftBiometrics ( hri_msgs::SoftBiometricsConstPtr  biometrics)
private

Definition at line 116 of file face.cpp.

◆ roi()

NormROI Face::roi ( ) const

Returns the normalized 2D region of interest (RoI) of the face.

Use example:

HRIListener hri_listener;
auto faces = hri_listener.getFaces();
for (auto const& face : faces)
{
auto roi = face.second.lock()->roi();
cout << "Normalized size of face_" << face.first << ": ";
cout << (roi.xmax - roi.xmin) << "x" << (roi.ymax - roi.ymin) << endl;
}

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

Definition at line 78 of file face.cpp.

◆ transform()

boost::optional< geometry_msgs::TransformStamped > Face::transform ( ) const

Returns the (stamped) 3D transform of the face (if available).

Definition at line 140 of file face.cpp.

Member Data Documentation

◆ _reference_frame

std::string hri::Face::_reference_frame
private

Definition at line 204 of file face.h.

◆ _tf_buffer_ptr

tf2_ros::Buffer* hri::Face::_tf_buffer_ptr
private

Definition at line 205 of file face.h.

◆ aligned_

cv::Mat hri::Face::aligned_
private

Definition at line 191 of file face.h.

◆ aligned_subscriber_

ros::Subscriber hri::Face::aligned_subscriber_
private

Definition at line 189 of file face.h.

◆ cropped_

cv::Mat hri::Face::cropped_
private

Definition at line 187 of file face.h.

◆ cropped_subscriber_

ros::Subscriber hri::Face::cropped_subscriber_
private

Definition at line 185 of file face.h.

◆ facial_action_units_

std::array<IntensityConfidence, 99> hri::Face::facial_action_units_
private

Definition at line 202 of file face.h.

◆ facial_landmarks_

std::array<hri_msgs::NormalizedPointOfInterest2D, 70> hri::Face::facial_landmarks_
private

Definition at line 195 of file face.h.

◆ landmarks_subscriber_

ros::Subscriber hri::Face::landmarks_subscriber_
private

Definition at line 193 of file face.h.

◆ nb_roi

size_t hri::Face::nb_roi
private

Definition at line 179 of file face.h.

◆ roi_

NormROI hri::Face::roi_
private

Definition at line 183 of file face.h.

◆ roi_subscriber_

ros::Subscriber hri::Face::roi_subscriber_
private

Definition at line 181 of file face.h.

◆ softbiometrics_

hri_msgs::SoftBiometricsConstPtr hri::Face::softbiometrics_
private

Definition at line 199 of file face.h.

◆ softbiometrics_subscriber_

ros::Subscriber hri::Face::softbiometrics_subscriber_
private

Definition at line 197 of file face.h.


The documentation for this class was generated from the following files:
hri::face
@ face
Definition: base.h:47
hri::Face::roi
NormROI roi() const
Returns the normalized 2D region of interest (RoI) of the face.
Definition: face.cpp:78


libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58