#include <face.h>
|
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< Gender > | gender () const |
|
void | init () override |
|
cv::Rect | roi () const |
| Returns the 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 () |
|
| FeatureTracker (ID id, const ros::NodeHandle &nh) |
|
| FeatureTracker (const FeatureTracker &)=delete |
|
std::string | getNamespace () const |
|
ID | id () const |
|
std::string | ns () const |
|
bool | operator< (const FeatureTracker &other) const |
|
virtual | ~FeatureTracker () |
|
Definition at line 68 of file face.h.
◆ Face()
◆ ~Face()
◆ age()
boost::optional< float > Face::age |
( |
| ) |
const |
◆ 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()
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 151 of file face.h.
◆ facialLandmarks()
boost::optional<std::array<hri_msgs::NormalizedPointOfInterest2D, 70> > hri::Face::facialLandmarks |
( |
| ) |
const |
|
inline |
◆ frame()
std::string hri::Face::frame |
( |
| ) |
const |
|
inline |
the name of the tf frame that correspond to this face
Definition at line 78 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 86 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 |
◆ init()
◆ onAligned()
void Face::onAligned |
( |
sensor_msgs::ImageConstPtr |
roi | ) |
|
|
private |
◆ onCropped()
void Face::onCropped |
( |
sensor_msgs::ImageConstPtr |
roi | ) |
|
|
private |
◆ onLandmarks()
void Face::onLandmarks |
( |
hri_msgs::FacialLandmarksConstPtr |
landmarks | ) |
|
|
private |
◆ onRoI()
void Face::onRoI |
( |
sensor_msgs::RegionOfInterestConstPtr |
roi | ) |
|
|
private |
◆ onSoftBiometrics()
void Face::onSoftBiometrics |
( |
hri_msgs::SoftBiometricsConstPtr |
biometrics | ) |
|
|
private |
◆ roi()
cv::Rect Face::roi |
( |
| ) |
const |
Returns the 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 <<
"Size of face_" <<
face.first <<
": ";
cout <<
roi.width <<
"x" <<
roi.height << 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.
◆ _reference_frame
std::string hri::Face::_reference_frame |
|
private |
◆ _tf_buffer_ptr
◆ aligned_
cv::Mat hri::Face::aligned_ |
|
private |
◆ aligned_subscriber_
◆ cropped_
cv::Mat hri::Face::cropped_ |
|
private |
◆ cropped_subscriber_
◆ facial_action_units_
◆ facial_landmarks_
std::array<hri_msgs::NormalizedPointOfInterest2D, 70> hri::Face::facial_landmarks_ |
|
private |
◆ landmarks_subscriber_
◆ nb_roi
◆ roi_
◆ roi_subscriber_
◆ softbiometrics_
hri_msgs::SoftBiometricsConstPtr hri::Face::softbiometrics_ |
|
private |
◆ softbiometrics_subscriber_
The documentation for this class was generated from the following files: