#include <voice.h>
|
| 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 () |
| |
| | 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 () |
| |
|
| void | _onSpeech (const hri_msgs::LiveSpeechConstPtr &) |
| |
Definition at line 49 of file voice.h.
◆ Voice()
◆ ~Voice()
◆ _onSpeech()
| void Voice::_onSpeech |
( |
const hri_msgs::LiveSpeechConstPtr & |
msg | ) |
|
|
private |
◆ 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()
◆ 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.
◆ _incremental_speech
| std::string hri::Voice::_incremental_speech |
|
private |
◆ _is_speaking
| bool hri::Voice::_is_speaking |
|
private |
◆ _reference_frame
| std::string hri::Voice::_reference_frame |
|
private |
◆ _speech
| std::string hri::Voice::_speech |
|
private |
◆ _tf_buffer_ptr
◆ incremental_speech_callbacks
| std::vector<std::function<void(const std::string&)> > hri::Voice::incremental_speech_callbacks |
|
private |
◆ is_speaking_callbacks
| std::vector<std::function<void(bool)> > hri::Voice::is_speaking_callbacks |
|
private |
◆ is_speaking_subscriber_
◆ speech_callbacks
| std::vector<std::function<void(const std::string&)> > hri::Voice::speech_callbacks |
|
private |
◆ speech_subscriber_
The documentation for this class was generated from the following files: