face.cpp
Go to the documentation of this file.
1 // Copyright 2022 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 #include "hri/face.h"
30 
31 #include <cv_bridge/cv_bridge.h>
32 #include "hri_msgs/SoftBiometrics.h"
33 
34 using namespace std;
35 using namespace hri;
36 
37 Face::Face(ID id, ros::NodeHandle& nh, tf2_ros::Buffer* tf_buffer_ptr,
38  const std::string& reference_frame)
39  : FeatureTracker{ id, nh }
40  , softbiometrics_(nullptr)
41  , _tf_buffer_ptr(tf_buffer_ptr)
42  , _reference_frame(reference_frame)
43 {
44 }
45 
47 {
48  ROS_DEBUG_STREAM("Deleting face " << id_);
50 }
51 
52 void Face::init()
53 {
54  ns_ = "/humans/faces/" + id_;
55  ROS_DEBUG_STREAM("New face detected: " << ns_);
56 
57  roi_subscriber_ = node_.subscribe<hri_msgs::NormalizedRegionOfInterest2D>(
58  ns_ + "/roi", 1, bind(&Face::onRoI, this, _1));
59 
60  cropped_subscriber_ = node_.subscribe<sensor_msgs::Image>(
61  ns_ + "/cropped", 1, bind(&Face::onCropped, this, _1));
62 
63  aligned_subscriber_ = node_.subscribe<sensor_msgs::Image>(
64  ns_ + "/aligned", 1, bind(&Face::onAligned, this, _1));
65 
66  landmarks_subscriber_ = node_.subscribe<hri_msgs::FacialLandmarks>(
67  ns_ + "/landmarks", 1, bind(&Face::onLandmarks, this, _1));
68 
69  softbiometrics_subscriber_ = node_.subscribe<hri_msgs::SoftBiometrics>(
70  ns_ + "/softbiometrics", 1, bind(&Face::onSoftBiometrics, this, _1));
71 }
72 
73 void Face::onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
74 {
75  roi_ = *roi;
76 }
77 
79 {
80  return roi_;
81 }
82 
83 void Face::onCropped(sensor_msgs::ImageConstPtr msg)
84 {
85  cropped_ = cv_bridge::toCvCopy(msg)->image; // if using toCvShare, the image ends up shared with aligned_!
86 }
87 
88 cv::Mat Face::cropped() const
89 {
90  return cropped_;
91 }
92 
93 void Face::onAligned(sensor_msgs::ImageConstPtr msg)
94 {
95  aligned_ = cv_bridge::toCvCopy(msg)->image; // if using toCvShare, the image ends up shared with cropped_!
96 }
97 
98 cv::Mat Face::aligned() const
99 {
100  return aligned_;
101 }
102 
103 void Face::onLandmarks(hri_msgs::FacialLandmarksConstPtr msg)
104 {
105  int i = 0;
106 
107  for (auto landmark : msg->landmarks)
108  {
109  facial_landmarks_[i].x = landmark.x;
110  facial_landmarks_[i].y = landmark.y;
111  facial_landmarks_[i].c = landmark.c;
112  ++i;
113  }
114 }
115 
116 void Face::onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics)
117 {
118  softbiometrics_ = biometrics;
119 }
120 
121 
122 boost::optional<float> Face::age() const
123 {
124  if (!softbiometrics_)
125  return boost::optional<float>();
126 
127  return softbiometrics_->age;
128 }
129 
130 boost::optional<Gender> Face::gender() const
131 {
132  if (!softbiometrics_)
133  return boost::optional<Gender>();
134  if (softbiometrics_->gender == 0) // UNDEFINED
135  return boost::optional<Gender>();
136 
137  return static_cast<Gender>(softbiometrics_->gender);
138 }
139 
140 boost::optional<geometry_msgs::TransformStamped> Face::transform() const
141 {
142  try
143  {
146 
147  return transform;
148  }
149  catch (tf2::LookupException)
150  {
151  ROS_WARN_STREAM("failed to transform the face frame " << frame() << " to " << _reference_frame
152  << ". Are the frames published?");
153  return boost::optional<geometry_msgs::TransformStamped>();
154  }
155 }
156 
157 boost::optional<geometry_msgs::TransformStamped> Face::gazeTransform() const
158 {
159  try
160  {
163 
164  return transform;
165  }
166  catch (tf2::LookupException)
167  {
168  ROS_WARN_STREAM("failed to transform the gaze frame " << frame() << " to " << _reference_frame
169  << ". Are the frames published?");
170  return boost::optional<geometry_msgs::TransformStamped>();
171  }
172 }
173 
hri::Face::frame
std::string frame() const
the name of the tf frame that correspond to this face
Definition: face.h:80
hri::FeatureTracker::id
ID id() const
Definition: base.h:88
hri::Face::softbiometrics_
hri_msgs::SoftBiometricsConstPtr softbiometrics_
Definition: face.h:199
hri
Definition: base.h:38
hri::FeatureTracker
Definition: base.h:52
hri::Gender
Gender
Definition: face.h:58
face.h
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
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
ros::Subscriber::shutdown
void shutdown()
hri::Face::aligned_
cv::Mat aligned_
Definition: face.h:191
hri::Face::onSoftBiometrics
void onSoftBiometrics(hri_msgs::SoftBiometricsConstPtr biometrics)
Definition: face.cpp:116
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
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
hri::Face::init
void init() override
Definition: face.cpp:52
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
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
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
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
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf2::LookupException
hri::Face::onRoI
void onRoI(hri_msgs::NormalizedRegionOfInterest2DConstPtr roi)
Definition: face.cpp:73
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::Face::cropped_
cv::Mat cropped_
Definition: face.h:187
hri::Face::_tf_buffer_ptr
tf2_ros::Buffer * _tf_buffer_ptr
Definition: face.h:205
ros::Time
std
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
cv_bridge.h
hri::ID
std::string ID
Definition: base.h:40
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
hri::Face::onLandmarks
void onLandmarks(hri_msgs::FacialLandmarksConstPtr landmarks)
Definition: face.cpp:103
hri::FeatureTracker::ns_
std::string ns_
Definition: base.h:119
hri::Face::roi
NormROI roi() const
Returns the normalized 2D region of interest (RoI) of the face.
Definition: face.cpp:78
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
ros::NodeHandle
hri::Face::gender
boost::optional< Gender > gender() const
Definition: face.cpp:130
hri::FeatureTracker::node_
ros::NodeHandle node_
Definition: base.h:121
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