Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
hri::Person Class Reference

#include <person.h>

Inheritance diagram for hri::Person:
Inheritance graph
[legend]

Public Member Functions

ID alias () const
 
boost::optional< bool > anonymous () const
 
BodyWeakConstPtr body () const
 
boost::optional< EngagementLevelengagement_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 HRIListenerlistener_
 
ros::Subscriber loc_confidence_subscriber_
 
ros::Subscriber voice_id_subscriber_
 
- Protected Attributes inherited from hri::FeatureTracker
ID id_
 
ros::NodeHandle node_
 
std::string ns_
 

Detailed Description

Definition at line 71 of file person.h.

Constructor & Destructor Documentation

◆ Person()

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.

◆ ~Person()

Person::~Person ( )
virtual

Definition at line 55 of file person.cpp.

Member Function Documentation

◆ alias()

ID hri::Person::alias ( ) const
inline

Definition at line 105 of file person.h.

◆ anonymous()

boost::optional<bool> hri::Person::anonymous ( ) const
inline

Definition at line 100 of file person.h.

◆ body()

BodyWeakConstPtr Person::body ( ) const

Definition at line 99 of file person.cpp.

◆ engagement_status()

boost::optional< EngagementLevel > Person::engagement_status ( ) const

Definition at line 115 of file person.cpp.

◆ face()

FaceWeakConstPtr Person::face ( ) const

Definition at line 91 of file person.cpp.

◆ frame()

std::string hri::Person::frame ( ) const
inline

Definition at line 79 of file person.h.

◆ init()

void Person::init ( )
overridevirtual

Implements hri::FeatureTracker.

Definition at line 60 of file person.cpp.

◆ location_confidence()

float hri::Person::location_confidence ( ) const
inline

Definition at line 112 of file person.h.

◆ tfCallback()

void hri::Person::tfCallback ( const geometry_msgs::TransformStampedConstPtr &  transform_ptr)
inlineprotected

Definition at line 132 of file person.h.

◆ transform()

boost::optional< geometry_msgs::TransformStamped > Person::transform ( ) const

Definition at line 141 of file person.cpp.

◆ voice()

VoiceWeakConstPtr Person::voice ( ) const

Definition at line 107 of file person.cpp.

Member Data Documentation

◆ _alias

ID hri::Person::_alias
protected

Definition at line 140 of file person.h.

◆ _anonymous

boost::optional<bool> hri::Person::_anonymous
protected

Definition at line 142 of file person.h.

◆ _engagement_status

hri_msgs::EngagementLevelConstPtr hri::Person::_engagement_status
protected

Definition at line 144 of file person.h.

◆ _loc_confidence

float hri::Person::_loc_confidence
protected

Definition at line 146 of file person.h.

◆ _reference_frame

std::string hri::Person::_reference_frame
protected

Definition at line 148 of file person.h.

◆ _tf_buffer_ptr

tf2_ros::Buffer* hri::Person::_tf_buffer_ptr
protected

Definition at line 158 of file person.h.

◆ alias_subscriber_

ros::Subscriber hri::Person::alias_subscriber_
protected

Definition at line 154 of file person.h.

◆ anonymous_subscriber_

ros::Subscriber hri::Person::anonymous_subscriber_
protected

Definition at line 153 of file person.h.

◆ body_id

ID hri::Person::body_id

Definition at line 121 of file person.h.

◆ body_id_subscriber_

ros::Subscriber hri::Person::body_id_subscriber_
protected

Definition at line 151 of file person.h.

◆ engagement_subscriber_

ros::Subscriber hri::Person::engagement_subscriber_
protected

Definition at line 155 of file person.h.

◆ face_id

ID hri::Person::face_id

Definition at line 120 of file person.h.

◆ face_id_subscriber_

ros::Subscriber hri::Person::face_id_subscriber_
protected

Definition at line 150 of file person.h.

◆ listener_

const HRIListener* hri::Person::listener_
protected

Definition at line 130 of file person.h.

◆ loc_confidence_subscriber_

ros::Subscriber hri::Person::loc_confidence_subscriber_
protected

Definition at line 156 of file person.h.

◆ voice_id

ID hri::Person::voice_id

Definition at line 122 of file person.h.

◆ voice_id_subscriber_

ros::Subscriber hri::Person::voice_id_subscriber_
protected

Definition at line 152 of file person.h.


The documentation for this class was generated from the following files:


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