Go to the documentation of this file.
   33 #include <geometry_msgs/TransformStamped.h> 
   34 #include <hri_msgs/LiveSpeech.h> 
   37 #include <boost/optional.hpp> 
   53         const std::string& reference_frame);
 
   67   boost::optional<geometry_msgs::TransformStamped> 
transform() 
const;
 
  112   void onSpeech(std::function<
void(
const std::string&)> callback)
 
  126   void init() 
override;
 
  140   void _onSpeech(
const hri_msgs::LiveSpeechConstPtr&);
 
  
std::shared_ptr< const Voice > VoiceConstPtr
std::vector< std::function< void(const std::string &)> > incremental_speech_callbacks
std::string _incremental_speech
std::string _reference_frame
ros::Subscriber speech_subscriber_
std::weak_ptr< Voice > VoiceWeakPtr
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the estimated (stamped) 3D transform of the voice (if available).
std::vector< std::function< void(const std::string &)> > speech_callbacks
bool is_speaking() const
returns speech is currently detected in this voice, ie, whether the person is currently speaking.
std::vector< std::function< void(bool)> > is_speaking_callbacks
std::weak_ptr< const Voice > VoiceWeakConstPtr
void _onSpeech(const hri_msgs::LiveSpeechConstPtr &)
std::string frame() const
the name of the tf frame that correspond to this body
const static ros::Duration VOICE_TF_TIMEOUT(0.01)
std::string speech() const
returns the last recognised final sentence (or an empty string if no speech was recognised yet).
std::string incremental_speech() const
returns the last recognised incremental sentence (or an empty string if no speech was recognised yet)...
void onIncrementalSpeech(std::function< void(const std::string &)> callback)
Registers a callback function, to be invoked everytime speech is recognised from this voice....
void onSpeech(std::function< void(const std::string &)> callback)
Registers a callback function, to be invoked everytime speech is recognised from this voice....
const static std::string VOICE_TF_PREFIX("voice_")
tf2_ros::Buffer * _tf_buffer_ptr
void onSpeaking(std::function< void(bool)> callback)
Registers a callback function, to be invoked everytime speech is detected (ie, the person is speaking...
ros::Subscriber is_speaking_subscriber_
std::shared_ptr< Voice > VoicePtr
Voice(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
libhri
Author(s): Séverin Lemaignan 
autogenerated on Thu Jul 6 2023 02:43:58