#include <person.h>

Public Member Functions | |
| ID | alias () const |
| boost::optional< bool > | anonymous () const |
| BodyWeakConstPtr | body () const |
| boost::optional< EngagementLevel > | engagement_status () const |
| FaceWeakConstPtr | face () const |
| std::string | frame () const |
| void | init () override |
| float | location_confidence () const |
| Person (ID id, const HRIListener *listener, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame) | |
| boost::optional< geometry_msgs::TransformStamped > | transform () const |
| VoiceWeakConstPtr | voice () const |
| virtual | ~Person () |
Public Member Functions inherited from hri::FeatureTracker | |
| FeatureTracker (const FeatureTracker &)=delete | |
| FeatureTracker (ID id, const ros::NodeHandle &nh) | |
| std::string | getNamespace () const |
| ID | id () const |
| std::string | ns () const |
| bool | operator< (const FeatureTracker &other) const |
| virtual | ~FeatureTracker () |
Public Attributes | |
| ID | body_id |
| ID | face_id |
| ID | voice_id |
Protected Member Functions | |
| void | tfCallback (const geometry_msgs::TransformStampedConstPtr &transform_ptr) |
Protected Attributes | |
| ID | _alias |
| boost::optional< bool > | _anonymous |
| hri_msgs::EngagementLevelConstPtr | _engagement_status |
| float | _loc_confidence |
| std::string | _reference_frame |
| tf2_ros::Buffer * | _tf_buffer_ptr |
| ros::Subscriber | alias_subscriber_ |
| ros::Subscriber | anonymous_subscriber_ |
| ros::Subscriber | body_id_subscriber_ |
| ros::Subscriber | engagement_subscriber_ |
| ros::Subscriber | face_id_subscriber_ |
| const HRIListener * | listener_ |
| ros::Subscriber | loc_confidence_subscriber_ |
| ros::Subscriber | voice_id_subscriber_ |
Protected Attributes inherited from hri::FeatureTracker | |
| ID | id_ |
| ros::NodeHandle | node_ |
| std::string | ns_ |
| Person::Person | ( | ID | id, |
| const HRIListener * | listener, | ||
| ros::NodeHandle & | nh, | ||
| tf2_ros::Buffer * | tf_buffer_ptr, | ||
| const std::string & | reference_frame | ||
| ) |
Definition at line 42 of file person.cpp.
|
virtual |
Definition at line 55 of file person.cpp.
|
inline |
| BodyWeakConstPtr Person::body | ( | ) | const |
Definition at line 99 of file person.cpp.
| boost::optional< EngagementLevel > Person::engagement_status | ( | ) | const |
Definition at line 115 of file person.cpp.
| FaceWeakConstPtr Person::face | ( | ) | const |
Definition at line 91 of file person.cpp.
|
overridevirtual |
Implements hri::FeatureTracker.
Definition at line 60 of file person.cpp.
|
inlineprotected |
| boost::optional< geometry_msgs::TransformStamped > Person::transform | ( | ) | const |
Definition at line 141 of file person.cpp.
| VoiceWeakConstPtr Person::voice | ( | ) | const |
Definition at line 107 of file person.cpp.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |