Class Face

Inheritance Relationships

Base Types

Class Documentation

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

Public Functions

Face(ID id, NodeInterfaces node_interfaces, rclcpp::CallbackGroup::SharedPtr callback_group, const tf2::BufferCore &tf_buffer, const std::string &reference_frame)
virtual ~Face()
inline std::string gazeFrame() const

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

inline std::optional<cv::Rect2f> roi() const

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

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

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

Returns the face image, if necessary scaled, centered and 0-padded, (if available).

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

Returns the face image, if necessary scaled, centered and 0-padded, (if available).

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

inline std::optional<FacialLandmarks> facialLandmarks() const

The list of the 70 facial landmarks (2D points, expressed in normalized coordinates), (if available).

Constants defined in hri_msgs/msgs/facial_landmarks.hpp can be used to access specific points on the face.

inline std::optional<FacialActionUnits> facialActionUnits() const

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.

inline std::optional<float> age() const

Estimated age of this face, if available (eg, the ‘/softbiometrics’ is published).

inline std::optional<Gender> gender() const

Estimated gender of this face, if available (eg, the ‘/softbiometrics’ is published).

inline std::optional<Expression> expression() const

The face expression as a discrete state.

inline std::optional<ExpressionVA> expressionVA() const

The face expression as a continuous value in the circumplex model space.

inline std::optional<float> expressionConfidence() const

The confidence of the face expression estimation.

std::optional<geometry_msgs::msg::TransformStamped> gazeTransform() const

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