Public Member Functions | Private Member Functions | Private Attributes | List of all members
hri::HRIListener Class Reference

Main entry point to libhri. This is most likely what you want to use. Use example: More...

#include <hri.h>

Public Member Functions

std::map< ID, BodyWeakConstPtrgetBodies () const
 Returns the list of currently detected bodies, mapped to their IDs. More...
 
std::map< ID, FaceWeakConstPtrgetFaces () const
 Returns the list of currently detected faces, mapped to their IDs. More...
 
std::map< ID, PersonWeakConstPtrgetPersons () 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. More...
 
std::map< ID, PersonWeakConstPtrgetTrackedPersons () const
 Returns the list of currently detected persons, mapped to their IDs. More...
 
std::map< ID, VoiceWeakConstPtrgetVoices () const
 Returns the list of currently detected voices, mapped to their IDs. More...
 
 HRIListener ()
 
void onBody (std::function< void(BodyWeakConstPtr)> callback)
 Registers a callback function, to be invoked everytime a new body is detected. More...
 
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) More...
 
void onFace (std::function< void(FaceWeakConstPtr)> callback)
 Registers a callback function, to be invoked everytime a new face is detected. More...
 
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) More...
 
void onPerson (std::function< void(PersonWeakConstPtr)> callback)
 Registers a callback function, to be invoked everytime a new person is detected. More...
 
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. More...
 
void onTrackedPerson (std::function< void(PersonWeakConstPtr)> callback)
 Registers a callback function, to be invoked everytime a new person is detected and actively tracked (eg, currently seen). More...
 
void onTrackedPersonLost (std::function< void(ID)> callback)
 Registers a callback function, to be invoked everytime a previously tracked person is lost. More...
 
void onVoice (std::function< void(VoiceWeakPtr)> callback)
 Registers a callback function, to be invoked everytime a new voice is detected. More...
 
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) More...
 
void setReferenceFrame (const std::string &frame)
 
 ~HRIListener ()
 

Private Member Functions

void init ()
 
void onTrackedFeature (FeatureType feature, hri_msgs::IdsListConstPtr tracked)
 

Private Attributes

std::string _reference_frame
 
tf2_ros::Buffer _tf_buffer
 
tf2_ros::TransformListener _tf_listener
 
std::map< ID, BodyConstPtrbodies
 
std::vector< std::function< void(BodyWeakConstPtr)> > body_callbacks
 
std::vector< std::function< void(ID)> > body_lost_callbacks
 
std::vector< std::function< void(FaceWeakConstPtr)> > face_callbacks
 
std::vector< std::function< void(ID)> > face_lost_callbacks
 
std::map< ID, FaceConstPtrfaces
 
std::map< FeatureType, ros::Subscriberfeature_subscribers_
 
ros::NodeHandle node_
 
std::vector< std::function< void(PersonConstPtr)> > person_callbacks
 
std::vector< std::function< void(ID)> > person_lost_callbacks
 
std::vector< std::function< void(PersonConstPtr)> > person_tracked_callbacks
 
std::vector< std::function< void(ID)> > person_tracked_lost_callbacks
 
std::map< ID, PersonConstPtrpersons
 
std::map< ID, PersonConstPtrtracked_persons
 
std::vector< std::function< void(VoiceWeakPtr)> > voice_callbacks
 
std::vector< std::function< void(ID)> > voice_lost_callbacks
 
std::map< ID, VoiceConstPtrvoices
 

Detailed Description

Main entry point to libhri. This is most likely what you want to use. Use example:

ros::init(argc, argv, "test_libhri");
HRIListener hri_listener;
while (ros::ok()) {
auto faces = hri_listener.getFaces();
for (auto const& face : faces)
{
cout << "Face " << face.first << " seen!";
}
}

Definition at line 70 of file hri.h.

Constructor & Destructor Documentation

◆ HRIListener()

HRIListener::HRIListener ( )

Definition at line 44 of file hri.cpp.

◆ ~HRIListener()

HRIListener::~HRIListener ( )

Definition at line 49 of file hri.cpp.

Member Function Documentation

◆ getBodies()

map< ID, BodyWeakConstPtr > HRIListener::getBodies ( ) const

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

Bodies are returned as constant std::weak_ptr as they may disappear at any point.

Definition at line 76 of file hri.cpp.

◆ getFaces()

map< ID, FaceWeakConstPtr > HRIListener::getFaces ( ) const

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

Faces are returned as constant std::weak_ptr as they may disappear at any point.

Definition at line 62 of file hri.cpp.

◆ getPersons()

map< ID, PersonWeakConstPtr > HRIListener::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.

Persons are returned as constant std::weak_ptr: while person do not disappear in general, anonymous persons (created because, eg, a face has been detected, and we can infer a yet-to-be-recognised person does exist) can disappear.

Definition at line 104 of file hri.cpp.

◆ getTrackedPersons()

map< ID, PersonWeakConstPtr > HRIListener::getTrackedPersons ( ) const

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

Persons are returned as constant std::weak_ptr: while person do not disappear in general, anonymous persons (created because, eg, a face has been detected, and we can infer a yet-to-be-recognised person does exist) can disappear.

Definition at line 139 of file hri.cpp.

◆ getVoices()

map< ID, VoiceWeakConstPtr > HRIListener::getVoices ( ) const

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

Voices are returned as constant std::weak_ptr as they may disappear at any point.

Definition at line 90 of file hri.cpp.

◆ init()

void HRIListener::init ( )
private

Definition at line 174 of file hri.cpp.

◆ onBody()

void hri::HRIListener::onBody ( std::function< void(BodyWeakConstPtr)>  callback)
inline

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

Definition at line 109 of file hri.h.

◆ onBodyLost()

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

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

Definition at line 117 of file hri.h.

◆ onFace()

void hri::HRIListener::onFace ( std::function< void(FaceWeakConstPtr)>  callback)
inline

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

Definition at line 86 of file hri.h.

◆ onFaceLost()

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

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

Definition at line 94 of file hri.h.

◆ onPerson()

void hri::HRIListener::onPerson ( std::function< void(PersonWeakConstPtr)>  callback)
inline

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

Definition at line 161 of file hri.h.

◆ onPersonLost()

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

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.

Definition at line 170 of file hri.h.

◆ onTrackedFeature()

void HRIListener::onTrackedFeature ( FeatureType  feature,
hri_msgs::IdsListConstPtr  tracked 
)
private

Definition at line 200 of file hri.cpp.

◆ onTrackedPerson()

void hri::HRIListener::onTrackedPerson ( std::function< void(PersonWeakConstPtr)>  callback)
inline

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

Definition at line 187 of file hri.h.

◆ onTrackedPersonLost()

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

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

Definition at line 195 of file hri.h.

◆ onVoice()

void hri::HRIListener::onVoice ( std::function< void(VoiceWeakPtr)>  callback)
inline

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

Definition at line 132 of file hri.h.

◆ onVoiceLost()

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

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

Definition at line 140 of file hri.h.

◆ setReferenceFrame()

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

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

By default, base_link.

Definition at line 206 of file hri.h.

Member Data Documentation

◆ _reference_frame

std::string hri::HRIListener::_reference_frame
private

Definition at line 241 of file hri.h.

◆ _tf_buffer

tf2_ros::Buffer hri::HRIListener::_tf_buffer
private

Definition at line 242 of file hri.h.

◆ _tf_listener

tf2_ros::TransformListener hri::HRIListener::_tf_listener
private

Definition at line 243 of file hri.h.

◆ bodies

std::map<ID, BodyConstPtr> hri::HRIListener::bodies
private

Definition at line 224 of file hri.h.

◆ body_callbacks

std::vector<std::function<void(BodyWeakConstPtr)> > hri::HRIListener::body_callbacks
private

Definition at line 225 of file hri.h.

◆ body_lost_callbacks

std::vector<std::function<void(ID)> > hri::HRIListener::body_lost_callbacks
private

Definition at line 226 of file hri.h.

◆ face_callbacks

std::vector<std::function<void(FaceWeakConstPtr)> > hri::HRIListener::face_callbacks
private

Definition at line 221 of file hri.h.

◆ face_lost_callbacks

std::vector<std::function<void(ID)> > hri::HRIListener::face_lost_callbacks
private

Definition at line 222 of file hri.h.

◆ faces

std::map<ID, FaceConstPtr> hri::HRIListener::faces
private

Definition at line 220 of file hri.h.

◆ feature_subscribers_

std::map<FeatureType, ros::Subscriber> hri::HRIListener::feature_subscribers_
private

Definition at line 218 of file hri.h.

◆ node_

ros::NodeHandle hri::HRIListener::node_
private

Definition at line 212 of file hri.h.

◆ person_callbacks

std::vector<std::function<void(PersonConstPtr)> > hri::HRIListener::person_callbacks
private

Definition at line 235 of file hri.h.

◆ person_lost_callbacks

std::vector<std::function<void(ID)> > hri::HRIListener::person_lost_callbacks
private

Definition at line 236 of file hri.h.

◆ person_tracked_callbacks

std::vector<std::function<void(PersonConstPtr)> > hri::HRIListener::person_tracked_callbacks
private

Definition at line 238 of file hri.h.

◆ person_tracked_lost_callbacks

std::vector<std::function<void(ID)> > hri::HRIListener::person_tracked_lost_callbacks
private

Definition at line 239 of file hri.h.

◆ persons

std::map<ID, PersonConstPtr> hri::HRIListener::persons
private

Definition at line 234 of file hri.h.

◆ tracked_persons

std::map<ID, PersonConstPtr> hri::HRIListener::tracked_persons
private

Definition at line 237 of file hri.h.

◆ voice_callbacks

std::vector<std::function<void(VoiceWeakPtr)> > hri::HRIListener::voice_callbacks
private

Definition at line 231 of file hri.h.

◆ voice_lost_callbacks

std::vector<std::function<void(ID)> > hri::HRIListener::voice_lost_callbacks
private

Definition at line 232 of file hri.h.

◆ voices

std::map<ID, VoiceConstPtr> hri::HRIListener::voices
private

Definition at line 228 of file hri.h.


The documentation for this class was generated from the following files:
hri::HRIListener::faces
std::map< ID, FaceConstPtr > faces
Definition: hri.h:220
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
hri::HRIListener::HRIListener
HRIListener()
Definition: hri.cpp:44
ros::ok
ROSCPP_DECL bool ok()
hri::face
@ face
Definition: base.h:47
ros::NodeHandle


libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58