33 #include <hri_msgs/NormalizedPointOfInterest2D.h> 34 #include <hri_msgs/FacialLandmarks.h> 35 #include <hri_msgs/SoftBiometrics.h> 36 #include <sensor_msgs/RegionOfInterest.h> 37 #include <sensor_msgs/Image.h> 39 #include <boost/optional.hpp> 44 #include <opencv2/core.hpp> 72 const std::string& reference_frame);
111 cv::Rect roi()
const;
117 cv::Mat cropped()
const;
124 cv::Mat aligned()
const;
134 boost::optional<std::array<hri_msgs::NormalizedPointOfInterest2D, 70>>
facialLandmarks()
const 136 return facial_landmarks_;
153 return facial_action_units_;
159 boost::optional<float> age()
const;
164 boost::optional<Gender> gender()
const;
168 boost::optional<geometry_msgs::TransformStamped> transform()
const;
172 boost::optional<geometry_msgs::TransformStamped> gazeTransform()
const;
174 void init()
override;
180 void onRoI(sensor_msgs::RegionOfInterestConstPtr roi);
184 void onCropped(sensor_msgs::ImageConstPtr roi);
188 void onAligned(sensor_msgs::ImageConstPtr roi);
192 void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks);
196 void onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics);
std::array< IntensityConfidence, 99 > facial_action_units_
hri_msgs::SoftBiometricsConstPtr softbiometrics_
static const std::string FACE_TF_PREFIX("face_")
void init(const M_string &remappings)
boost::optional< std::array< IntensityConfidence, 99 > > facialActionUnits() const
the list of the facial action units detected on the face.
std::weak_ptr< const Face > FaceWeakConstPtr
ros::Subscriber cropped_subscriber_
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
ros::Subscriber landmarks_subscriber_
std::shared_ptr< Face > FacePtr
static const std::string GAZE_TF_PREFIX("gaze_")
ros::Subscriber aligned_subscriber_
tf2_ros::Buffer * _tf_buffer_ptr
ros::Subscriber roi_subscriber_
std::string _reference_frame
boost::optional< std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > > facialLandmarks() const
the list of the 66 facial landmarks (2D points, expressed in normalised coordinates).
std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > facial_landmarks_
ros::Subscriber softbiometrics_subscriber_
static const ros::Duration FACE_TF_TIMEOUT(0.01)
std::string frame() const
the name of the tf frame that correspond to this face
std::weak_ptr< Face > FaceWeakPtr