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/FacialLandmarks.h>
35 #include <hri_msgs/SoftBiometrics.h>
36 #include <sensor_msgs/RegionOfInterest.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 namespace hri
49 {
51 {
52  float intensity;
53  float confidence;
54 };
55 
56 enum Gender
57 {
58  FEMALE = 1,
59  MALE = 2,
60  OTHER = 3
61 };
62 
63 // the tf prefixes follow REP-155
64 const static std::string FACE_TF_PREFIX("face_");
65 const static std::string GAZE_TF_PREFIX("gaze_");
66 const static ros::Duration FACE_TF_TIMEOUT(0.01);
67 
68 class Face : public FeatureTracker
69 {
70 public:
71  Face(ID id, ros::NodeHandle& nh, tf2_ros::Buffer* tf_buffer_ptr,
72  const std::string& reference_frame);
73 
74  virtual ~Face();
75 
78  std::string frame() const
79  {
80  return FACE_TF_PREFIX + id_;
81  }
82 
86  std::string gazeFrame() const
87  {
88  return GAZE_TF_PREFIX + id_;
89  }
90 
111  cv::Rect roi() const;
112 
113 
117  cv::Mat cropped() const;
118 
124  cv::Mat aligned() const;
125 
134  boost::optional<std::array<hri_msgs::NormalizedPointOfInterest2D, 70>> facialLandmarks() const
135  {
136  return facial_landmarks_;
137  }
138 
151  boost::optional<std::array<IntensityConfidence, 99>> facialActionUnits() const
152  {
153  return facial_action_units_;
154  }
155 
156  /* \brief estimated age of this face, if available (eg, the
157  * '/softbiometrics' is published)
158  */
159  boost::optional<float> age() const;
160 
161  /* \brief estimated gender of this face, if available (eg, the
162  * '/softbiometrics' is published)
163  */
164  boost::optional<Gender> gender() const;
165 
168  boost::optional<geometry_msgs::TransformStamped> transform() const;
169 
172  boost::optional<geometry_msgs::TransformStamped> gazeTransform() const;
173 
174  void init() override;
175 
176 private:
177  size_t nb_roi;
178 
180  void onRoI(sensor_msgs::RegionOfInterestConstPtr roi);
181  cv::Rect roi_;
182 
184  void onCropped(sensor_msgs::ImageConstPtr roi);
185  cv::Mat cropped_;
186 
188  void onAligned(sensor_msgs::ImageConstPtr roi);
189  cv::Mat aligned_;
190 
192  void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks);
193  std::array<hri_msgs::NormalizedPointOfInterest2D, 70> facial_landmarks_;
194 
196  void onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics);
197  hri_msgs::SoftBiometricsConstPtr softbiometrics_;
198 
199 
200  std::array<IntensityConfidence, 99> facial_action_units_;
201 
202  std::string _reference_frame;
204 };
205 
206 typedef std::shared_ptr<Face> FacePtr;
207 typedef std::shared_ptr<const Face> FaceConstPtr;
208 typedef std::weak_ptr<Face> FaceWeakPtr;
209 typedef std::weak_ptr<const Face> FaceWeakConstPtr;
210 
211 } // namespace hri
212 #endif
std::array< IntensityConfidence, 99 > facial_action_units_
Definition: face.h:200
hri_msgs::SoftBiometricsConstPtr softbiometrics_
Definition: face.h:197
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.
Definition: face.h:151
std::weak_ptr< const Face > FaceWeakConstPtr
Definition: face.h:209
ros::Subscriber cropped_subscriber_
Definition: face.h:183
std::string gazeFrame() const
the name of the tf frame that correspond to the gaze direction and orientation of the face ...
Definition: face.h:86
size_t nb_roi
Definition: face.h:177
std::shared_ptr< const Face > FaceConstPtr
Definition: face.h:207
ros::Subscriber landmarks_subscriber_
Definition: face.h:191
cv::Mat aligned_
Definition: face.h:189
std::shared_ptr< Face > FacePtr
Definition: face.h:206
Gender
Definition: face.h:56
Definition: face.h:59
static const std::string GAZE_TF_PREFIX("gaze_")
ros::Subscriber aligned_subscriber_
Definition: face.h:187
tf2_ros::Buffer * _tf_buffer_ptr
Definition: face.h:203
ros::Subscriber roi_subscriber_
Definition: face.h:179
std::string _reference_frame
Definition: face.h:202
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:134
cv::Mat cropped_
Definition: face.h:185
Definition: base.h:38
cv::Rect roi_
Definition: face.h:181
std::array< hri_msgs::NormalizedPointOfInterest2D, 70 > facial_landmarks_
Definition: face.h:193
ros::Subscriber softbiometrics_subscriber_
Definition: face.h:195
static const ros::Duration FACE_TF_TIMEOUT(0.01)
std::string ID
Definition: base.h:40
Definition: face.h:68
std::string frame() const
the name of the tf frame that correspond to this face
Definition: face.h:78
std::weak_ptr< Face > FaceWeakPtr
Definition: face.h:208


libhri
Author(s): Séverin Lemaignan
autogenerated on Wed Apr 19 2023 02:30:41