libhri (C++)

class HRIListener : public std::enable_shared_from_this<HRIListener>

Main entry point to libhri.

This is most likely what you want to use.

Public Functions

std::map<ID, FacePtr> getFaces() const

Returns the list of currently detected faces, mapped to their IDs.

inline void onFace(std::function<void(FacePtr)> callback)

Registers a callback function, to be invoked everytime a new face is detected.

inline void onFaceLost(std::function<void(ID)> callback)

Registers a callback function, to be invoked everytime a previously tracked face is lost (eg, not detected anymore)

std::map<ID, BodyPtr> getBodies() const

Returns the list of currently detected bodies, mapped to their IDs.

inline void onBody(std::function<void(BodyPtr)> callback)

Registers a callback function, to be invoked everytime a new body is detected.

inline void onBodyLost(std::function<void(ID)> callback)

Registers a callback function, to be invoked everytime a previously tracked body is lost (eg, not detected anymore)

std::map<ID, VoicePtr> getVoices() const

Returns the list of currently detected voices, mapped to their IDs.

inline void onVoice(std::function<void(VoicePtr)> callback)

Registers a callback function, to be invoked everytime a new voice is detected.

inline void onVoiceLost(std::function<void(ID)> callback)

Registers a callback function, to be invoked everytime a previously tracked voice is lost (eg, not detected anymore)

std::map<ID, PersonPtr> getPersons() const

Returns the list of all known persons, whether or not they are currently actively detected (eg, seen).

The persons are mapped to their IDs.

inline void onPerson(std::function<void(PersonPtr)> callback)

Registers a callback function, to be invoked everytime a new person is detected.

inline void onPersonLost(std::function<void(ID)> callback)

Registers a callback function, to be invoked everytime a person is lost.

This can only happen for anonymous persons. Identified persons will never be removed from the list of all known persons.

std::map<ID, PersonPtr> getTrackedPersons() const

Returns the list of currently detected persons, mapped to their IDs.

inline void onTrackedPerson(std::function<void(PersonPtr)> callback)

Registers a callback function, to be invoked everytime a new person is detected and actively tracked (eg, currently seen).

inline void onTrackedPersonLost(std::function<void(ID)> callback)

Registers a callback function, to be invoked everytime a previously tracked person is lost.

inline void setReferenceFrame(const std::string &frame)

Sets the reference frame from which the TF transformations of the persons will be returned (via Person::transform()).

By default, base_link.

inline rclcpp::CallbackGroup::SharedPtr getCallbackGroup()

Get the mutually exclusive callback group used by HRIListener.

This can be used to avoid race conditions between the internal subscribe callbacks and the HRIListener getter functions (e.g., hri::HRIListener::getTrackedPersons(), hri::Face::roi()). If a multithreaded executor is used to freely spin a node which interfaces are used by both HRIListener and by timer/topic/… callbacks which call an HRIListener getter function, then the latter should be added to this callback group.

inline void clearData()

Clears internal data, but leaves the registered callbacks.

inline void clearCallbacks()

Clears the registered callbacks.

Public Static Functions

static inline std::shared_ptr<HRIListener> create(NodeLikeSharedPtr node_like)

Factory function for the libhri main class.

The class can subscribe to topics and print logs, using the node interfaces arguments. The class uses a factory design pattern to make sure a shared pointer to an instance of this class is created, enabling the safe internal use of shared_from_this(). See https://en.cppreference.com/w/cpp/memory/enable_shared_from_this for more info.

Internally the HRIListener uses node interfaces to adapt both to Node and LifecycleNode (see tinyurl.com/ROSCon-2023-node-interfaces). Since rclcpp::NodeInterface is not available in Humble, for convenience we use a variant for this factory and internally pass a structure mocking rclcpp::NodeInterface.

class Person : public hri::FeatureTracker, public std::enable_shared_from_this<Person>

Public Functions

ConstFacePtr face() const

Returns a shared pointer to the face of this person, or a nullptr if this person is currently not associated to any detected face.

ConstBodyPtr body() const

Returns a shared pointer to the body of this person, or a nullptr if this person is currently not associated to any detected body.

ConstVoicePtr voice() const

Returns a shared pointer to the voice of this person, or a nullptr if this person is currently not associated to any detected voice.

virtual std::optional<geometry_msgs::msg::TransformStamped> transform() const override

Returns the estimated (stamped) 3D transform of self (if available).

class Face : public hri::FeatureTracker, public std::enable_shared_from_this<Face>

Public Functions

inline std::string gazeFrame() const

The name of the tf frame that correspond to the gaze direction and orientation of the face.

inline std::optional<cv::Rect2f> roi() const

Returns the normalized 2D region of interest (RoI) of the face, (if available).

The pixel coordinates are provided in the original camera’s image coordinate space.

inline std::optional<cv::Mat> cropped() const

Returns the face image, if necessary scaled, centered and 0-padded, (if available).

inline std::optional<cv::Mat> aligned() const

Returns the face image, if necessary scaled, centered and 0-padded, (if available).

In addition, the face is rotated so that the eyes are horizontal.

inline std::optional<FacialLandmarks> facialLandmarks() const

The list of the 70 facial landmarks (2D points, expressed in normalized coordinates), (if available).

Constants defined in hri_msgs/msgs/facial_landmarks.hpp can be used to access specific points on the face.

inline std::optional<FacialActionUnits> facialActionUnits() const

the list of the facial action units detected on the face.

Action units indices follow the Action Unit naming convention by Ekman. List here: https://en.wikipedia.org/wiki/Facial_Action_Coding_System

Note that the list is sparse (some indices do not exist in Ekman classification). In addition, depending on the AU detector, some action units might not be detected. In these cases, the confidence value will be 0.

inline std::optional<float> age() const

Estimated age of this face, if available (eg, the ‘/softbiometrics’ is published).

inline std::optional<Gender> gender() const

Estimated gender of this face, if available (eg, the ‘/softbiometrics’ is published).

inline std::optional<Expression> expression() const

The face expression as a discrete state.

inline std::optional<ExpressionVA> expressionVA() const

The face expression as a continuous value in the circumplex model space.

inline std::optional<float> expressionConfidence() const

The confidence of the face expression estimation.

std::optional<geometry_msgs::msg::TransformStamped> gazeTransform() const

Returns the (stamped) 3D transform of the gaze (if available).

class Body : public hri::FeatureTracker, public std::enable_shared_from_this<Body>

Public Functions

inline std::optional<cv::Rect2f> roi() const

If available, returns the normalized 2D region of interest (RoI) of the body.

The coordinates are provided in the original camera’s image coordinate space.

inline std::optional<cv::Mat> cropped() const

Returns the body image, cropped from the source image.

inline std::optional<SkeletalKeypoints> skeleton() const

Returns the 2D skeleton keypoints.

Points coordinates are in the image space of the source image, and normalised between 0.0 and 1.0.

The skeleton joints indices follow those defined in http://docs.ros.org/en/api/hri_msgs/html/msg/Skeleton2D.html

inline std::optional<std::string> bodyDescription() const

Returns the body kinematic description in URDF format.

The body kinematic description follows the template defined in http://www.ros.org/reps/rep-0155.html#kinematic-model-of-the-human

class Voice : public hri::FeatureTracker, public std::enable_shared_from_this<Voice>

Public Functions

inline std::optional<bool> isSpeaking() const

Returns speech is currently detected in this voice, ie, whether the person is currently speaking.

inline std::optional<std::string> speech() const

Returns the last recognised final sentence.

inline std::optional<std::string> incrementalSpeech() const

Returns the last recognised incremental sentence.

inline std::optional<std::string> locale() const

Returns the last recognised speech locale.

inline void onSpeaking(std::function<void(bool)> callback)

Registers a callback function, to be invoked everytime speech is detected.

See also:

inline void onSpeech(std::function<void(const std::string&, const std::string&)> callback)

Registers a callback function, to be invoked everytime a full speech is detected.

Only final sentences for this voice are returned, for instance at the end of a sentence. The callback takes two arguments:

  1. the recognised speech text,

  2. the locale.

See also: Voice::onIncrementalSpeech for incremental feedback

inline void onSpeech(std::function<void(const std::string&)> callback)

Deprecated:

Use void onSpeech(std::function<void(const std::string &, const std::string &)> callback).

inline void onIncrementalSpeech(std::function<void(const std::string&, const std::string&)> callback)

Registers a callback function, to be invoked everytime speech any speech is detected.

The callback will be triggered every time the speech recogniser returns a result, even if it is not the final result. The callback takes two arguments:

  1. the recognised speech text,

  2. the locale.

See also: Voice::onSpeech for final feedback

inline void onIncrementalSpeech(std::function<void(const std::string&)> callback)

Deprecated:

Use void onSpeech(std::function<void(const std::string &, const std::string &)> callback).

inline void clearCallbacks()

Clears the registered callbacks.

typedef std::string hri::ID
typedef std::shared_ptr<Person> hri::PersonPtr
typedef std::shared_ptr<const Person> hri::ConstPersonPtr
typedef std::shared_ptr<Face> hri::FacePtr
typedef std::shared_ptr<const Face> hri::ConstFacePtr
typedef std::shared_ptr<Body> hri::BodyPtr
typedef std::shared_ptr<const Body> hri::ConstBodyPtr
typedef std::shared_ptr<Voice> hri::VoicePtr
typedef std::shared_ptr<const Voice> hri::ConstVoicePtr
enum class hri::Expression

Values:

enumerator kNeutral
enumerator kAngry
enumerator kSad
enumerator kHappy
enumerator kSurprised
enumerator kDisgusted
enumerator kScared
enumerator kPleading
enumerator kVulnerable
enumerator kDespaired
enumerator kGuilty
enumerator kDisappointed
enumerator kEmbarrassed
enumerator kHorrified
enumerator kSkeptical
enumerator kAnnoyed
enumerator kFurious
enumerator kSuspicious
enumerator kRejected
enumerator kBored
enumerator kTired
enumerator kAsleep
enumerator kConfused
enumerator kAmazed
enumerator kExcited
struct ExpressionVA

Public Members

float valence

Valence dimension of the circumplex model of affect, from -1.0 to 1.0.

float arousal

Arousal dimension of the circumplex model of affect, from -1.0 to 1.0.

enum class hri::EngagementLevel

Values:

enumerator kDisengaged

the human has not looked in the direction of the robot

enumerator kEngaging

the human has started to look in the direction of the robot

enumerator kEngaged

the human is fully engaged with the robot

enumerator kDisengaging

the human has started to look away from the robot

enum class hri::Gender

Values:

enumerator kFemale
enumerator kMale
enumerator kOther
typedef std::map<SkeletalKeypoint, PointOfInterest> hri::SkeletalKeypoints
enum class hri::SkeletalKeypoint

Values:

enumerator kNose
enumerator kNeck
enumerator kRightShoulder
enumerator kRightElbow
enumerator kRightWrist
enumerator kLeftShoulder
enumerator kLeftElbow
enumerator kLeftWrist
enumerator kRightHip
enumerator kRightKnee
enumerator kRightAnkle
enumerator kLeftHip
enumerator kLeftKnee
enumerator kLeftAnkle
enumerator kLeftEye
enumerator kRightEye
enumerator kLeftEar
enumerator kRightEar
typedef std::map<FacialLandmark, PointOfInterest> hri::FacialLandmarks
enum class hri::FacialLandmark

Values:

enumerator kRightEar
enumerator kRightProfile1
enumerator kRightProfile2
enumerator kRightProfile3
enumerator kRightProfile4
enumerator kRightProfile5
enumerator kRightProfile6
enumerator kRightProfile7
enumerator kMenton
enumerator kLeftEar
enumerator kLeftProfile1
enumerator kLeftProfile2
enumerator kLeftProfile3
enumerator kLeftProfile4
enumerator kLeftProfile5
enumerator kLeftProfile6
enumerator kLeftProfile7
enumerator kRightEyebrowOutside
enumerator kRightEyebrow1
enumerator kRightEyebrow2
enumerator kRightEyebrow3
enumerator kRightEyebrowInside
enumerator kRightEyeOutside
enumerator kRightEyeTop1
enumerator kRightEyeTop2
enumerator kRightEyeInside
enumerator kRightEyeBottom1
enumerator kRightEyeBottom2
enumerator kRightPupil
enumerator kLeftEyebrowOutside
enumerator kLeftEyebrow1
enumerator kLeftEyebrow2
enumerator kLeftEyebrow3
enumerator kLeftEyebrowInside
enumerator kLeftEyeOutside
enumerator kLeftEyeTop1
enumerator kLeftEyeTop2
enumerator kLeftEyeInside
enumerator kLeftEyeBottom1
enumerator kLeftEyeBottom2
enumerator kLeftPupil
enumerator kSellion
enumerator kNose1
enumerator kNose2
enumerator kNose
enumerator kNostril1
enumerator kNostril2
enumerator kNostril3
enumerator kNostril4
enumerator kNostril5
enumerator kMouthOuterRight
enumerator kMouthOuterTop1
enumerator kMouthOuterTop2
enumerator kMouthOuterTop3
enumerator kMouthOuterTop4
enumerator kMouthOuterTop5
enumerator kMouthOuterLeft
enumerator kMouthOuterBottom1
enumerator kMouthOuterBottom2
enumerator kMouthOuterBottom3
enumerator kMouthOuterBottom4
enumerator kMouthOuterBottom5
enumerator kMouthInnerRight
enumerator kMouthInnerTop1
enumerator kMouthInnerTop2
enumerator kMouthInnerTop3
enumerator kMouthInnerLeft
enumerator kMouthInnerBottom1
enumerator kMouthInnerBottom2
enumerator kMouthInnerBottom3
typedef std::map<FacialActionUnit, IntensityConfidence> hri::FacialActionUnits
enum class hri::FacialActionUnit

Values:

enumerator kNeutralFace
enumerator kInnerBrowRaiser
enumerator kOuterBrowRaiser
enumerator kBrowLowerer
enumerator kUpperLidRaiser
enumerator kCheeckRaiser
enumerator kLidTightener
enumerator kLipsTowardEachOther
enumerator kNoseWrinkler
enumerator kUpperLipRaiser
enumerator kNasolabialDeepener
enumerator kLipCornerPuller
enumerator kSharpLipPuller
enumerator kDimpler
enumerator kLipCornerDepressor
enumerator kLowerLipDepressor
enumerator kChinRaiser
enumerator kLipPucker
enumerator kTongueShow
enumerator kLipStretcher
enumerator kNeckTightener
enumerator kLipFunneler
enumerator kLipTightener
enumerator kLipPressor
enumerator kLipsPart
enumerator kJawDrop
enumerator kMouthStretch
enumerator kLipSuck
enumerator kHeadTurnLeft
enumerator kHeadTurnRight
enumerator kHeadUp
enumerator kHeadDown
enumerator kHeadTiltLeft
enumerator kHeadTiltRight
enumerator kHeadForward
enumerator kHeadBack
enumerator kEyesTurnLeft
enumerator kEyesTurnRight
enumerator kEyesUp
enumerator kEyesDown
enumerator kWalleye
enumerator kCrossEye
enumerator kEyesPositionedToLookAtOtherPerson
enumerator kBrownsAndForeheadNotVisible
enumerator kEyesNotVisible
enumerator kLowerFaceNotVisible
enumerator kEntireFaceNotVisible
enumerator kUnsociable
enumerator kJawThrust
enumerator kJawSideways
enumerator kJawClencher
enumerator kLipBite
enumerator kCheekBlow
enumerator kCheekPuff
enumerator kCheekSuck
enumerator kTongueBulge
enumerator kLipWipe
enumerator kNostrilDilator
enumerator kNostrilCompressor
enumerator kSniff
enumerator kLidDroop
enumerator kSlit
enumerator kEyesClosed
enumerator kSquint
enumerator kBlink
enumerator kWink
enumerator kSpeech
enumerator kSwallow
enumerator kChewing
enumerator kShoulderShrug
enumerator kHeadShakeBackAndForth
enumerator kHeadNodUpAndDown
enumerator kFlash
enumerator kPartialFlash
enumerator kShiverTremble
enumerator kFastUpDownLook
struct IntensityConfidence

Public Members

float intensity

Intensity value (0.0 to 1.0)

float confidence

Confidence value (0.0 to 1.0)

struct PointOfInterest

Public Members

float x

Normalized x coordinate.

float y

Normalized y coordinate.

float c

Confidence value.