.. _program_listing_file_include_hri_face.hpp: Program Listing for File face.hpp ================================= |exhale_lsh| :ref:`Return to documentation for file ` (``include/hri/face.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright (c) 2023 PAL Robotics S.L. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef HRI__FACE_HPP_ #define HRI__FACE_HPP_ #include #include #include #include "geometry_msgs/msg/transform_stamped.hpp" #include "hri_msgs/msg/expression.hpp" #include "hri_msgs/msg/facial_action_units.hpp" #include "hri_msgs/msg/facial_landmarks.hpp" #include "hri_msgs/msg/normalized_region_of_interest2_d.hpp" #include "hri_msgs/msg/soft_biometrics.hpp" #include "opencv2/core.hpp" #include "rclcpp/rclcpp.hpp" #include "sensor_msgs/msg/image.hpp" #include "tf2_ros/buffer.h" #include "hri/feature_tracker.hpp" #include "hri/types.hpp" namespace hri { // TODO(LJU): possibly subscribe also to the /frontalized sub-topic class Face : public FeatureTracker, public std::enable_shared_from_this { friend class HRIListener; // for invalidate() public: Face( ID id, NodeInterfaces node_interfaces, rclcpp::CallbackGroup::SharedPtr callback_group, const tf2::BufferCore & tf_buffer, const std::string & reference_frame); virtual ~Face(); std::string gazeFrame() const {return kGazeFrame_;} std::optional roi() const {return roi_;} std::optional cropped() const {return cropped_;} std::optional aligned() const {return aligned_;} std::optional facialLandmarks() const {return landmarks_;} std::optional facialActionUnits() const {return facial_action_units_;} std::optional age() const {return age_;} std::optional gender() const {return gender_;} std::optional expression() const {return expression_;} std::optional expressionVA() const {return expression_va_;} std::optional expressionConfidence() const {return expression_confidence_;} std::optional gazeTransform() const; private: void onRoI(hri_msgs::msg::NormalizedRegionOfInterest2D::ConstSharedPtr msg); void onCropped(sensor_msgs::msg::Image::ConstSharedPtr msg); void onAligned(sensor_msgs::msg::Image::ConstSharedPtr msg); void onLandmarks(hri_msgs::msg::FacialLandmarks::ConstSharedPtr msg); void onSoftBiometrics(hri_msgs::msg::SoftBiometrics::ConstSharedPtr msg); void onFacs(hri_msgs::msg::FacialActionUnits::ConstSharedPtr msg); void onExpression(hri_msgs::msg::Expression::ConstSharedPtr msg); void invalidate(); std::optional roi_; std::optional cropped_; std::optional aligned_; std::optional landmarks_; std::optional age_; std::optional gender_; std::optional facial_action_units_; std::optional expression_; std::optional expression_va_; std::optional expression_confidence_; rclcpp::Subscription::SharedPtr roi_subscriber_; rclcpp::Subscription::SharedPtr cropped_subscriber_; rclcpp::Subscription::SharedPtr aligned_subscriber_; rclcpp::Subscription::SharedPtr landmarks_subscriber_; rclcpp::Subscription::SharedPtr softbiometrics_subscriber_; rclcpp::Subscription::SharedPtr facial_action_units_subscriber_; rclcpp::Subscription::SharedPtr expression_subscriber_; const std::string kGazeFrame_; }; typedef std::shared_ptr FacePtr; typedef std::shared_ptr ConstFacePtr; } // namespace hri #endif // HRI__FACE_HPP_