Class Voice

Inheritance Relationships

Base Types

Class Documentation

class Voice : public hri::FeatureTracker, public std::enable_shared_from_this<Voice>

Public Functions

Voice(ID id, NodeInterfaces node_interfaces, rclcpp::CallbackGroup::SharedPtr callback_group, const tf2::BufferCore &tf_buffer, const std::string &reference_frame)
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:

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.