Go to the documentation of this file.
34 #include <hri_msgs/IdsList.h>
81 std::map<ID, FaceWeakConstPtr>
getFaces()
const;
104 std::map<ID, BodyWeakConstPtr>
getBodies()
const;
127 std::map<ID, VoiceWeakConstPtr>
getVoices()
const;
156 std::map<ID, PersonWeakConstPtr>
getPersons()
const;
std::vector< std::function< void(PersonConstPtr)> > person_callbacks
std::map< ID, FaceConstPtr > faces
std::vector< std::function< void(BodyWeakConstPtr)> > body_callbacks
std::map< ID, PersonConstPtr > tracked_persons
std::vector< std::function< void(ID)> > body_lost_callbacks
std::vector< std::function< void(ID)> > person_lost_callbacks
std::vector< std::function< void(ID)> > person_tracked_lost_callbacks
std::map< ID, PersonConstPtr > persons
std::weak_ptr< Voice > VoiceWeakPtr
void onFaceLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked face is lost (eg,...
std::map< ID, BodyConstPtr > bodies
std::map< ID, BodyWeakConstPtr > getBodies() const
Returns the list of currently detected bodies, mapped to their IDs.
std::map< ID, PersonWeakConstPtr > getPersons() const
Returns the list of all known persons, whether or not they are currently actively detected (eg,...
void onTrackedPerson(std::function< void(PersonWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new person is detected and actively tracked ...
std::map< ID, PersonWeakConstPtr > getTrackedPersons() const
Returns the list of currently detected persons, mapped to their IDs.
std::shared_ptr< const Person > PersonConstPtr
tf2_ros::TransformListener _tf_listener
std::weak_ptr< const Face > FaceWeakConstPtr
std::vector< std::function< void(PersonConstPtr)> > person_tracked_callbacks
void onVoiceLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked voice is lost (eg,...
std::string _reference_frame
void onBody(std::function< void(BodyWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new body is detected.
void onFace(std::function< void(FaceWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new face is detected.
std::weak_ptr< const Body > BodyWeakConstPtr
std::vector< std::function< void(FaceWeakConstPtr)> > face_callbacks
std::vector< std::function< void(ID)> > voice_lost_callbacks
void onPersonLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a person is lost. This can only happen for ano...
void onBodyLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked body is lost (eg,...
void onPerson(std::function< void(PersonWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new person is detected.
std::weak_ptr< const Person > PersonWeakConstPtr
std::map< ID, FaceWeakConstPtr > getFaces() const
Returns the list of currently detected faces, mapped to their IDs.
std::map< FeatureType, ros::Subscriber > feature_subscribers_
Main entry point to libhri. This is most likely what you want to use. Use example:
void onTrackedPersonLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked person is lost.
std::map< ID, VoiceWeakConstPtr > getVoices() const
Returns the list of currently detected voices, mapped to their IDs.
tf2_ros::Buffer _tf_buffer
std::vector< std::function< void(ID)> > face_lost_callbacks
std::vector< std::function< void(VoiceWeakPtr)> > voice_callbacks
std::map< ID, VoiceConstPtr > voices
void onVoice(std::function< void(VoiceWeakPtr)> callback)
Registers a callback function, to be invoked everytime a new voice is detected.
void onTrackedFeature(FeatureType feature, hri_msgs::IdsListConstPtr tracked)
void setReferenceFrame(const std::string &frame)
libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58