face.h
Go to the documentation of this file.
1 // Copyright 2021 PAL Robotics S.L.
2 //
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 //
6 // * Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 //
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 //
13 // * Neither the name of the PAL Robotics S.L. nor the names of its
14 // contributors may be used to endorse or promote products derived from
15 // this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 
29 
30 #ifndef HRI_FACE_H
31 #define HRI_FACE_H
32 
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>
38 #include <memory>
39 #include <boost/optional.hpp>
40 
41 #include "base.h"
42 #include "ros/subscriber.h"
43 
44 #include <opencv2/core.hpp>
45 
47 
48 typedef hri_msgs::NormalizedRegionOfInterest2D NormROI;
49 
50 namespace hri
51 {
53 {
54  float intensity;
55  float confidence;
56 };
57 
58 enum Gender
59 {
60  FEMALE = 1,
61  MALE = 2,
62  OTHER = 3
63 };
64 
65 // the tf prefixes follow REP-155
66 const static std::string FACE_TF_PREFIX("face_");
67 const static std::string GAZE_TF_PREFIX("gaze_");
68 const static ros::Duration FACE_TF_TIMEOUT(0.01);
69 
70 class Face : public FeatureTracker
71 {
72 public:
73  Face(ID id, ros::NodeHandle& nh, tf2_ros::Buffer* tf_buffer_ptr,
74  const std::string& reference_frame);
75 
76  virtual ~Face();
77 
80  std::string frame() const
81  {
82  return FACE_TF_PREFIX + id_;
83  }
84 
88  std::string gazeFrame() const
89  {
90  return GAZE_TF_PREFIX + id_;
91  }
92 
113  NormROI roi() const;
114 
115 
119  cv::Mat cropped() const;
120 
126  cv::Mat aligned() const;
127 
136  boost::optional<std::array<hri_msgs::NormalizedPointOfInterest2D, 70>> facialLandmarks() const
137  {
138  return facial_landmarks_;
139  }
140 
153  boost::optional<std::array<IntensityConfidence, 99>> facialActionUnits() const
154  {
155  return facial_action_units_;
156  }
157 
158  /* \brief estimated age of this face, if available (eg, the
159  * '/softbiometrics' is published)
160  */
161  boost::optional<float> age() const;
162 
163  /* \brief estimated gender of this face, if available (eg, the
164  * '/softbiometrics' is published)
165  */
166  boost::optional<Gender> gender() const;
167 
170  boost::optional<geometry_msgs::TransformStamped> transform() const;
171 
174  boost::optional<geometry_msgs::TransformStamped> gazeTransform() const;
175 
176  void init() override;
177 
178 private:
179  size_t nb_roi;
180 
182  void onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr roi);
184 
186  void onCropped(sensor_msgs::ImageConstPtr roi);
187  cv::Mat cropped_;
188 
190  void onAligned(sensor_msgs::ImageConstPtr roi);
191  cv::Mat aligned_;
192 
194  void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks);
195  std::array<hri_msgs::NormalizedPointOfInterest2D, 70> facial_landmarks_;
196 
198  void onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics);
199  hri_msgs::SoftBiometricsConstPtr softbiometrics_;
200 
201 
202  std::array<IntensityConfidence, 99> facial_action_units_;
203 
204  std::string _reference_frame;
206 };
207 
208 typedef std::shared_ptr<Face> FacePtr;
209 typedef std::shared_ptr<const Face> FaceConstPtr;
210 typedef std::weak_ptr<Face> FaceWeakPtr;
211 typedef std::weak_ptr<const Face> FaceWeakConstPtr;
212 
213 } // namespace hri
214 #endif
hri::Face::frame
std::string frame() const
the name of the tf frame that correspond to this face
Definition: face.h:80
hri::Face::softbiometrics_
hri_msgs::SoftBiometricsConstPtr softbiometrics_
Definition: face.h:199
hri
Definition: base.h:38
hri::FeatureTracker
Definition: base.h:52
hri::IntensityConfidence::confidence
float confidence
Definition: face.h:55
hri::Gender
Gender
Definition: face.h:58
hri::Face::roi_
NormROI roi_
Definition: face.h:183
hri::Face::gazeFrame
std::string gazeFrame() const
the name of the tf frame that correspond to the gaze direction and orientation of the face
Definition: face.h:88
hri::FaceConstPtr
std::shared_ptr< const Face > FaceConstPtr
Definition: face.h:209
NormROI
hri_msgs::NormalizedRegionOfInterest2D NormROI
Definition: body.h:48
hri::Face::aligned
cv::Mat aligned() const
Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width a...
Definition: face.cpp:98
hri::Face::facialActionUnits
boost::optional< std::array< IntensityConfidence, 99 > > facialActionUnits() const
the list of the facial action units detected on the face.
Definition: face.h:153
hri::FEMALE
@ FEMALE
Definition: face.h:60
hri::IntensityConfidence::intensity
float intensity
Definition: face.h:54
hri::Face::Face
Face(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
Definition: face.cpp:37
hri::Face::nb_roi
size_t nb_roi
Definition: face.h:179
hri::Face
Definition: face.h:70
hri::Face::aligned_
cv::Mat aligned_
Definition: face.h:191
NormROI
hri_msgs::NormalizedRegionOfInterest2D NormROI
Definition: face.h:48
hri::Face::onSoftBiometrics
void onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics)
Definition: face.cpp:116
base.h
hri::Face::cropped_subscriber_
ros::Subscriber cropped_subscriber_
Definition: face.h:185
hri::Face::onAligned
void onAligned(sensor_msgs::ImageConstPtr roi)
Definition: face.cpp:93
hri::OTHER
@ OTHER
Definition: face.h:62
hri::Face::init
void init() override
Definition: face.cpp:52
hri::Face::onCropped
void onCropped(sensor_msgs::ImageConstPtr roi)
Definition: face.cpp:83
hri::Face::aligned_subscriber_
ros::Subscriber aligned_subscriber_
Definition: face.h:189
hri::FACE_TF_PREFIX
const static std::string FACE_TF_PREFIX("face_")
hri::FaceWeakConstPtr
std::weak_ptr< const Face > FaceWeakConstPtr
Definition: face.h:211
subscriber.h
hri::Face::roi_subscriber_
ros::Subscriber roi_subscriber_
Definition: face.h:181
hri::Face::landmarks_subscriber_
ros::Subscriber landmarks_subscriber_
Definition: face.h:193
hri::Face::_reference_frame
std::string _reference_frame
Definition: face.h:204
tf2_ros::Buffer
hri::Face::onRoI
void onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
Definition: face.cpp:73
hri::IntensityConfidence
Definition: face.h:52
hri::Face::facialLandmarks
boost::optional< std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > > facialLandmarks() const
the list of the 66 facial landmarks (2D points, expressed in normalised coordinates).
Definition: face.h:136
hri::Face::gazeTransform
boost::optional< geometry_msgs::TransformStamped > gazeTransform() const
Returns the (stamped) 3D transform of the gaze (if available).
Definition: face.cpp:157
hri::FaceWeakPtr
std::weak_ptr< Face > FaceWeakPtr
Definition: face.h:210
hri::Face::cropped_
cv::Mat cropped_
Definition: face.h:187
hri::Face::_tf_buffer_ptr
tf2_ros::Buffer * _tf_buffer_ptr
Definition: face.h:205
hri::FacePtr
std::shared_ptr< Face > FacePtr
Definition: face.h:208
transform_listener.h
hri::Face::cropped
cv::Mat cropped() const
Returns the face image, if necessary scaled, centered and 0-padded to match the /humans/faces/width a...
Definition: face.cpp:88
hri::ID
std::string ID
Definition: base.h:40
hri::GAZE_TF_PREFIX
const static std::string GAZE_TF_PREFIX("gaze_")
hri::Face::facial_landmarks_
std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > facial_landmarks_
Definition: face.h:195
hri::Face::age
boost::optional< float > age() const
Definition: face.cpp:122
hri::Face::softbiometrics_subscriber_
ros::Subscriber softbiometrics_subscriber_
Definition: face.h:197
hri::FACE_TF_TIMEOUT
const static ros::Duration FACE_TF_TIMEOUT(0.01)
hri::Face::~Face
virtual ~Face()
Definition: face.cpp:46
ros::Duration
hri::Face::onLandmarks
void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks)
Definition: face.cpp:103
hri::Face::roi
NormROI roi() const
Returns the normalized 2D region of interest (RoI) of the face.
Definition: face.cpp:78
ros::NodeHandle
ros::Subscriber
hri::Face::gender
boost::optional< Gender > gender() const
Definition: face.cpp:130
hri::MALE
@ MALE
Definition: face.h:61
hri::Face::facial_action_units_
std::array< IntensityConfidence, 99 > facial_action_units_
Definition: face.h:202
hri::FeatureTracker::id_
ID id_
Definition: base.h:116
hri::Face::transform
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the (stamped) 3D transform of the face (if available).
Definition: face.cpp:140


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