Class HRIListener
Defined in File hri.hpp
Inheritance Relationships
Base Type
public std::enable_shared_from_this< HRIListener >
Class Documentation
-
class HRIListener : public std::enable_shared_from_this<HRIListener>
Main entry point to libhri. This is most likely what you want to use.
See examples/node_show_faces.cpp for a minimal usage example
Public Functions
-
virtual ~HRIListener()
-
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
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.
Protected Functions
-
virtual ~HRIListener()