Main entry point to libhri. This is most likely what you want to use. Use example:
More...
|
std::map< ID, BodyWeakConstPtr > | getBodies () const |
| Returns the list of currently detected bodies, mapped to their IDs. More...
|
|
std::map< ID, FaceWeakConstPtr > | getFaces () const |
| Returns the list of currently detected faces, mapped to their IDs. More...
|
|
std::map< ID, PersonWeakConstPtr > | 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. More...
|
|
std::map< ID, PersonWeakConstPtr > | getTrackedPersons () const |
| Returns the list of currently detected persons, mapped to their IDs. More...
|
|
std::map< ID, VoiceWeakConstPtr > | getVoices () 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 () |
|
Main entry point to libhri. This is most likely what you want to use. Use example:
auto faces = hri_listener.getFaces();
{
cout <<
"Face " <<
face.first <<
" seen!";
}
}
Definition at line 70 of file hri.h.
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.
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.