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

#include <voice.h>

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

Public Member Functions

std::string frame () const
 the name of the tf frame that correspond to this body More...
 
std::string incremental_speech () const
 returns the last recognised incremental sentence (or an empty string if no speech was recognised yet). More...
 
void init () override
 
bool is_speaking () const
 returns speech is currently detected in this voice, ie, whether the person is currently speaking. More...
 
void onIncrementalSpeech (std::function< void(const std::string &)> callback)
 Registers a callback function, to be invoked everytime speech is recognised from this voice. The callback will be triggered every time the speech recogniser returns a result, even if it is not the final result. More...
 
void onSpeaking (std::function< void(bool)> callback)
 Registers a callback function, to be invoked everytime speech is detected (ie, the person is speaking). More...
 
void onSpeech (std::function< void(const std::string &)> callback)
 Registers a callback function, to be invoked everytime speech is recognised from this voice. Only final sentences are returned, eg for instance at the end of a sentece. More...
 
std::string speech () const
 returns the last recognised final sentence (or an empty string if no speech was recognised yet). More...
 
boost::optional< geometry_msgs::TransformStamped > transform () const
 Returns the estimated (stamped) 3D transform of the voice (if available). More...
 
 Voice (ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
 
virtual ~Voice ()
 
- 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 ()
 

Private Member Functions

void _onSpeech (const hri_msgs::LiveSpeechConstPtr &)
 

Private Attributes

std::string _incremental_speech
 
bool _is_speaking
 
std::string _reference_frame
 
std::string _speech
 
tf2_ros::Buffer_tf_buffer_ptr
 
std::vector< std::function< void(const std::string &)> > incremental_speech_callbacks
 
std::vector< std::function< void(bool)> > is_speaking_callbacks
 
ros::Subscriber is_speaking_subscriber_
 
std::vector< std::function< void(const std::string &)> > speech_callbacks
 
ros::Subscriber speech_subscriber_
 

Additional Inherited Members

- Protected Attributes inherited from hri::FeatureTracker
ID id_
 
ros::NodeHandle node_
 
std::string ns_
 

Detailed Description

Definition at line 49 of file voice.h.

Constructor & Destructor Documentation

◆ Voice()

Voice::Voice ( ID  id,
ros::NodeHandle nh,
tf2_ros::Buffer tf_buffer_ptr,
const std::string &  reference_frame 
)

Definition at line 35 of file voice.cpp.

◆ ~Voice()

Voice::~Voice ( )
virtual

Definition at line 41 of file voice.cpp.

Member Function Documentation

◆ _onSpeech()

void Voice::_onSpeech ( const hri_msgs::LiveSpeechConstPtr &  msg)
private

Definition at line 64 of file voice.cpp.

◆ frame()

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

the name of the tf frame that correspond to this body

Definition at line 59 of file voice.h.

◆ incremental_speech()

std::string hri::Voice::incremental_speech ( ) const
inline

returns the last recognised incremental sentence (or an empty string if no speech was recognised yet).

Definition at line 88 of file voice.h.

◆ init()

void Voice::init ( )
overridevirtual

Implements hri::FeatureTracker.

Definition at line 46 of file voice.cpp.

◆ is_speaking()

bool hri::Voice::is_speaking ( ) const
inline

returns speech is currently detected in this voice, ie, whether the person is currently speaking.

Definition at line 72 of file voice.h.

◆ onIncrementalSpeech()

void hri::Voice::onIncrementalSpeech ( std::function< void(const std::string &)>  callback)
inline

Registers a callback function, to be invoked everytime speech is recognised from this voice. The callback will be triggered every time the speech recogniser returns a result, even if it is not the final result.

Definition at line 121 of file voice.h.

◆ onSpeaking()

void hri::Voice::onSpeaking ( std::function< void(bool)>  callback)
inline

Registers a callback function, to be invoked everytime speech is detected (ie, the person is speaking).

See also:

Definition at line 101 of file voice.h.

◆ onSpeech()

void hri::Voice::onSpeech ( std::function< void(const std::string &)>  callback)
inline

Registers a callback function, to be invoked everytime speech is recognised from this voice. Only final sentences are returned, eg for instance at the end of a sentece.

See also: Voice::onIncrementalSpeech for incremental feedback

Definition at line 112 of file voice.h.

◆ speech()

std::string hri::Voice::speech ( ) const
inline

returns the last recognised final sentence (or an empty string if no speech was recognised yet).

Definition at line 80 of file voice.h.

◆ transform()

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

Returns the estimated (stamped) 3D transform of the voice (if available).

Definition at line 85 of file voice.cpp.

Member Data Documentation

◆ _incremental_speech

std::string hri::Voice::_incremental_speech
private

Definition at line 134 of file voice.h.

◆ _is_speaking

bool hri::Voice::_is_speaking
private

Definition at line 132 of file voice.h.

◆ _reference_frame

std::string hri::Voice::_reference_frame
private

Definition at line 129 of file voice.h.

◆ _speech

std::string hri::Voice::_speech
private

Definition at line 133 of file voice.h.

◆ _tf_buffer_ptr

tf2_ros::Buffer* hri::Voice::_tf_buffer_ptr
private

Definition at line 130 of file voice.h.

◆ incremental_speech_callbacks

std::vector<std::function<void(const std::string&)> > hri::Voice::incremental_speech_callbacks
private

Definition at line 138 of file voice.h.

◆ is_speaking_callbacks

std::vector<std::function<void(bool)> > hri::Voice::is_speaking_callbacks
private

Definition at line 136 of file voice.h.

◆ is_speaking_subscriber_

ros::Subscriber hri::Voice::is_speaking_subscriber_
private

Definition at line 142 of file voice.h.

◆ speech_callbacks

std::vector<std::function<void(const std::string&)> > hri::Voice::speech_callbacks
private

Definition at line 137 of file voice.h.

◆ speech_subscriber_

ros::Subscriber hri::Voice::speech_subscriber_
private

Definition at line 143 of file voice.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