Class Voice
Defined in File voice.hpp
Inheritance Relationships
Base Types
public hri::FeatureTracker
(Class FeatureTracker)public std::enable_shared_from_this< Voice >
Class Documentation
-
class Voice : public hri::FeatureTracker, public std::enable_shared_from_this<Voice>
Public Functions
-
virtual ~Voice()
-
inline std::optional<bool> isSpeaking() const
Returns speech is currently detected in this voice, ie, whether the person is currently speaking.
-
inline std::optional<std::string> speech() const
Returns the last recognised final sentence (or an empty string if no speech was recognised yet).
-
inline std::optional<std::string> incrementalSpeech() const
Returns the last recognised incremental sentence (or an empty string if no speech was recognised yet).
-
inline void onSpeaking(std::function<void(bool)> callback)
Registers a callback function, to be invoked everytime speech is detected (ie, the person is speaking).
See also:
Voice::onSpeech and Voice::onIncrementalSpeech to register a callback ot get the actual recognised speech
Voice::speech and Voice::incrementalSpeech for the last recognised speech
-
inline 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.
See also: Voice::onIncrementalSpeech for incremental feedback
-
inline 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.
-
virtual ~Voice()