Skip to content

S2S Agents

Overview

Agents in RAI are modular components that encapsulate specific functionalities and behaviors. They follow a consistent interface defined by the BaseAgent class and can be combined to create complex robotic systems. The Speech to Speech Agents are used for voice-based interaction, and communicate with other agents.

SpeechToSpeechAgent

SpeechToSpeechAgent is the abstract base class for locally deployable S2S Agents. It provides functionality to manage sound device integration, as well as defines the communication schema for integration with the rest of the system.

Class Definition

SpeechToSpeechAgent class definition

rai_s2s.s2s.agents.SpeechToSpeechAgent

Bases: BaseAgent

Source code in rai_s2s/s2s/agents/s2s_agent.py
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
class SpeechToSpeechAgent(BaseAgent):
    def __init__(
        self,
        from_human_topic: str,
        to_human_topic: str,
        *,
        microphone_config: SoundDeviceConfig,
        speaker_config: SoundDeviceConfig,
        transcription_model: BaseTranscriptionModel,
        vad: BaseVoiceDetectionModel,
        tts: TTSModel,
        grace_period: float = 1.0,
        logger: Optional[logging.Logger] = None,
        **kwargs,
    ):
        super().__init__()
        if logger is not None:
            self.logger = logger
        self.sound_connector = SoundDeviceConnector(
            targets=[("speaker", speaker_config)],
            sources=[("microphone", microphone_config)],
        )

        self.from_human_topic = from_human_topic
        self.to_human_topic = to_human_topic

        sample_rate, _, out_channels = self.sound_connector.get_audio_params("speaker")
        tts.sample_rate = sample_rate
        tts.channels = out_channels

        self.playback_data = PlayData()

        self.should_record_pipeline: List[BaseVoiceDetectionModel] = []
        self.should_stop_pipeline: List[BaseVoiceDetectionModel] = []

        self.current_transcription_id = str(uuid4())[0:8]
        self.current_speech_id = None
        self.text_queues: dict[str, Queue] = {self.current_transcription_id: Queue()}

        self.terminate_agent = Event()

        self.audio_generating_thread = Thread(target=self._audio_gen_thread)
        self.audio_generating_thread.start()
        self.audio_queues: dict[str, Queue] = {self.current_transcription_id: Queue()}
        self.remembered_speech_ids: list[str] = []

        self.tts_model = tts

        self.transcription_model = transcription_model

        self.vad: BaseVoiceDetectionModel = vad
        self.grace_period = grace_period
        self.grace_period_start = 0

        self.sample_buffer = []
        self.sample_buffer_lock = Lock()
        self.transcription_lock = Lock()
        self.active_thread = ""
        self.transcription_threads: dict[str, ThreadData] = {}
        self.transcription_buffers: dict[str, list[NDArray]] = {}
        self.is_playing = False

        self.recording_started = False
        # self.ran_setup = False

        self.hri_connector: HRIConnector = self._setup_hri_connector()

        self.microphone_samples: Optional[np.ndarray] = None
        self.save_flag = False

    @abstractmethod
    def _setup_hri_connector(self) -> HRIConnector: ...

    def _audio_gen_thread(self):
        while not self.terminate_agent.wait(timeout=0.01):
            if self.current_transcription_id in self.text_queues:
                try:
                    data = self.text_queues[self.current_transcription_id].get(
                        block=False
                    )
                except Empty:
                    continue
                audio = self.tts_model.get_speech(data)
                try:
                    self.audio_queues[self.current_transcription_id].put(audio)
                except KeyError as e:
                    self.logger.error(
                        f"Could not find queue for {self.current_transcription_id}: queuse: {self.audio_queues.keys()}"
                    )
                    raise e

    def run(self):
        """
        Start the text-to-speech agent, initializing playback and launching the transcription thread.
        """
        self.running = True
        self.logger.info("Starting SpeechToSpeechAgent...")

        msg = SoundDeviceMessage(read=False)
        self.player_handle = self.sound_connector.start_action(
            action_data=msg,
            target="speaker",
            on_feedback=self._speaker_callback,
            on_done=lambda: None,
        )
        msg = SoundDeviceMessage(read=True)
        self.listener_handle = self.sound_connector.start_action(
            action_data=msg,
            target="microphone",
            on_feedback=self._on_microphone_sample,
            on_done=lambda: None,
        )
        self.logger.info("SpeechToSpeechAgent Started!")

    def _speaker_callback(self, outdata, frames, time, status_dict):
        set_flags = [flag for flag, status in status_dict.items() if status]

        if set_flags:
            self.logger.warning("Flags set:" + ", ".join(set_flags))
        if self.playback_data.playing:
            if self.playback_data.current_segment is None:
                try:
                    self.playback_data.current_segment = self.audio_queues[
                        self.current_transcription_id
                    ].get(block=False)
                    self.playback_data.data = np.array(
                        self.playback_data.current_segment.get_array_of_samples()  # type: ignore
                    ).reshape(-1, self.playback_data.channels)
                except Empty:
                    pass
                except KeyError:
                    pass
            if self.playback_data.data is not None:
                current_frame = self.playback_data.current_frame
                chunksize = min(len(self.playback_data.data) - current_frame, frames)
                outdata[:chunksize] = self.playback_data.data[
                    current_frame : current_frame + chunksize
                ]
                if chunksize < frames:
                    outdata[chunksize:] = 0
                    self.playback_data.current_frame = 0
                    self.playback_data.current_segment = None
                    self.playback_data.data = None
                else:
                    self.playback_data.current_frame += chunksize

    def _on_microphone_sample(self, indata: np.ndarray, status_flags: dict[str, Any]):
        sample_time = time.time()
        with self.sample_buffer_lock:
            self.sample_buffer.append(indata)
            if not self.recording_started and len(self.sample_buffer) > 5:
                self.sample_buffer = self.sample_buffer[-5:]

        # attempt to join finished threads:
        for thread_id in self.transcription_threads:
            if self.transcription_threads[thread_id]["event"].is_set():
                self.transcription_threads[thread_id]["thread"].join()
                self.transcription_threads[thread_id]["joined"] = True

        voice_detected, output_parameters = self.vad(indata, {})
        self.logger.debug(f"Voice detected: {voice_detected}: {output_parameters}")
        should_record = False
        if voice_detected and not self.recording_started:
            should_record = self._should_record(indata, output_parameters)

        if should_record:
            self.logger.info("starting recording...")
            self.recording_started = True
            thread_id = str(uuid4())[0:8]
            transcription_thread = Thread(
                target=self._transcription_thread,
                args=[thread_id],
            )
            transcription_finished = Event()
            self.active_thread = thread_id
            self.transcription_threads[thread_id] = {
                "thread": transcription_thread,
                "event": transcription_finished,
                "transcription": "",
                "joined": False,
            }

        if voice_detected:
            self.logger.debug("Voice detected... resetting grace period")
            self.grace_period_start = sample_time
            self.set_playback_state("pause")
            self.is_playing = False
        if (
            self.recording_started
            and sample_time - self.grace_period_start > self.grace_period
        ):
            self.logger.info(
                "Grace period ended... stopping recording, starting transcription"
            )
            self.recording_started = False
            self.grace_period_start = 0
            with self.sample_buffer_lock:
                self.transcription_buffers[self.active_thread] = self.sample_buffer
                self.sample_buffer = []
            self.transcription_threads[self.active_thread]["thread"].start()
            self.active_thread = ""
            self.set_playback_state("stop")
            self.is_playing = False
        elif not self.is_playing and (
            sample_time - self.grace_period_start > self.grace_period
        ):
            self.set_playback_state("play")
            self.is_playing = True

    def _should_record(
        self, audio_data: NDArray, input_parameters: dict[str, Any]
    ) -> bool:
        if len(self.should_record_pipeline) == 0:
            return True
        for model in self.should_record_pipeline:
            detected, output = model(audio_data, input_parameters)
            self.logger.debug(f"detected {detected}, output {output}")
            if detected:
                model.reset()
                return True
        return False

    def _transcription_thread(self, identifier: str):
        self.logger.info(f"transcription thread {identifier} started")
        audio_data = np.concatenate(self.transcription_buffers[identifier])
        with (
            self.transcription_lock
        ):  # this is only necessary for the local model... TODO: fix this somehow
            transcription = self.transcription_model.transcribe(audio_data)
        self._send_from_human_message(transcription)
        self.transcription_threads[identifier]["transcription"] = transcription
        self.transcription_threads[identifier]["event"].set()

    @abstractmethod
    def _send_from_human_message(self, data: str): ...

    def _on_to_human_message(self, message: HRIMessage):
        self.logger.info(f"Receieved message from human: {message.text}")
        self.logger.warning(
            f"Starting playback, current id: {self.current_transcription_id}"
        )
        if (
            self.current_speech_id is None
            and message.communication_id is not None
            and message.communication_id not in self.remembered_speech_ids
        ):
            self.current_speech_id = message.communication_id
            self.remembered_speech_ids.append(self.current_speech_id)
            if len(self.remembered_speech_ids) > 64:
                self.remembered_speech_ids.pop(0)
        if self.current_speech_id == message.communication_id:
            self.text_queues[self.current_transcription_id].put(message.text)
        self.playback_data.playing = True

    def add_detection_model(self, model: BaseVoiceDetectionModel):
        """
        Add a voice detection model to check before recording starts.

        Parameters
        ----------
        model : BaseVoiceDetectionModel
            The voice detection model to be added.
        """

        self.should_record_pipeline.append(model)

    def set_playback_state(self, state: Literal["play", "pause", "stop"]):
        """
        Set the playback state of the system.

        Parameters
        ----------
        state : {"play", "pause", "stop"}
            The desired playback state:
            - "play": Start or resume playback.
            - "pause": Pause the current playback.
            - "stop": Stop playback and reset playback-related data and queues.

        Notes
        -----
        - When state is "stop", this method:
          - Resets the `current_speech_id`.
          - Generates a new `current_transcription_id`.
          - Initializes new audio and text queues.
          - Clears previous playback data.
        - Logs actions and transitions for debugging and monitoring purposes.
        """
        if state == "play":
            self.playback_data.playing = True
        elif state == "pause":
            self.playback_data.playing = False
        elif state == "stop":
            self.current_speech_id = None
            self.playback_data.playing = False
            previous_id = self.current_transcription_id
            self.logger.warning(f"Stopping playback, previous id: {previous_id}")
            self.current_transcription_id = str(uuid4())[0:8]
            self.audio_queues[self.current_transcription_id] = Queue()
            self.text_queues[self.current_transcription_id] = Queue()
            try:
                del self.audio_queues[previous_id]
                del self.text_queues[previous_id]
            except KeyError:
                pass
            self.playback_data.data = None
            self.playback_data.current_frame = 0
            self.playback_data.current_segment = None

        self.logger.debug(f"Current status is: {self.playback_data.playing}")

    def stop(self):
        """
        Clean exit the speech-to-speech agent, terminating playback and joining the transcription thread.
        """
        self.sound_connector.shutdown()

        self.logger.info("Stopping TextToSpeechAgent")
        self.terminate_agent.set()
        if self.audio_generating_thread is not None:
            self.audio_generating_thread.join()

add_detection_model(model)

Add a voice detection model to check before recording starts.

Parameters:

Name Type Description Default
model BaseVoiceDetectionModel

The voice detection model to be added.

required
Source code in rai_s2s/s2s/agents/s2s_agent.py
293
294
295
296
297
298
299
300
301
302
303
def add_detection_model(self, model: BaseVoiceDetectionModel):
    """
    Add a voice detection model to check before recording starts.

    Parameters
    ----------
    model : BaseVoiceDetectionModel
        The voice detection model to be added.
    """

    self.should_record_pipeline.append(model)

run()

Start the text-to-speech agent, initializing playback and launching the transcription thread.

Source code in rai_s2s/s2s/agents/s2s_agent.py
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
def run(self):
    """
    Start the text-to-speech agent, initializing playback and launching the transcription thread.
    """
    self.running = True
    self.logger.info("Starting SpeechToSpeechAgent...")

    msg = SoundDeviceMessage(read=False)
    self.player_handle = self.sound_connector.start_action(
        action_data=msg,
        target="speaker",
        on_feedback=self._speaker_callback,
        on_done=lambda: None,
    )
    msg = SoundDeviceMessage(read=True)
    self.listener_handle = self.sound_connector.start_action(
        action_data=msg,
        target="microphone",
        on_feedback=self._on_microphone_sample,
        on_done=lambda: None,
    )
    self.logger.info("SpeechToSpeechAgent Started!")

set_playback_state(state)

Set the playback state of the system.

Parameters:

Name Type Description Default
state (play, pause, stop)

The desired playback state: - "play": Start or resume playback. - "pause": Pause the current playback. - "stop": Stop playback and reset playback-related data and queues.

"play"
Notes
  • When state is "stop", this method:
  • Resets the current_speech_id.
  • Generates a new current_transcription_id.
  • Initializes new audio and text queues.
  • Clears previous playback data.
  • Logs actions and transitions for debugging and monitoring purposes.
Source code in rai_s2s/s2s/agents/s2s_agent.py
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
def set_playback_state(self, state: Literal["play", "pause", "stop"]):
    """
    Set the playback state of the system.

    Parameters
    ----------
    state : {"play", "pause", "stop"}
        The desired playback state:
        - "play": Start or resume playback.
        - "pause": Pause the current playback.
        - "stop": Stop playback and reset playback-related data and queues.

    Notes
    -----
    - When state is "stop", this method:
      - Resets the `current_speech_id`.
      - Generates a new `current_transcription_id`.
      - Initializes new audio and text queues.
      - Clears previous playback data.
    - Logs actions and transitions for debugging and monitoring purposes.
    """
    if state == "play":
        self.playback_data.playing = True
    elif state == "pause":
        self.playback_data.playing = False
    elif state == "stop":
        self.current_speech_id = None
        self.playback_data.playing = False
        previous_id = self.current_transcription_id
        self.logger.warning(f"Stopping playback, previous id: {previous_id}")
        self.current_transcription_id = str(uuid4())[0:8]
        self.audio_queues[self.current_transcription_id] = Queue()
        self.text_queues[self.current_transcription_id] = Queue()
        try:
            del self.audio_queues[previous_id]
            del self.text_queues[previous_id]
        except KeyError:
            pass
        self.playback_data.data = None
        self.playback_data.current_frame = 0
        self.playback_data.current_segment = None

    self.logger.debug(f"Current status is: {self.playback_data.playing}")

stop()

Clean exit the speech-to-speech agent, terminating playback and joining the transcription thread.

Source code in rai_s2s/s2s/agents/s2s_agent.py
349
350
351
352
353
354
355
356
357
358
def stop(self):
    """
    Clean exit the speech-to-speech agent, terminating playback and joining the transcription thread.
    """
    self.sound_connector.shutdown()

    self.logger.info("Stopping TextToSpeechAgent")
    self.terminate_agent.set()
    if self.audio_generating_thread is not None:
        self.audio_generating_thread.join()

Communication

The Agent communicates through two communication channels provided during initialization - from_human and to_human. On the from_human channel text transcribed from human voice is published. On the to_human channel receives text to be played to the human through text-to-speech.

Voice interaction

The voice interaction is performed through two audio streams, with two devices. These devices can be different, but don't have to - and in case of most local deployments they will be the same. The list of available sounddevices for configuration can be obtained by running python -c "import sounddevice as sd; print(sd.query_devices())". The configuration requires the user to specify the name of the sound device to be used for interfacing. This is the entire string from the index until the comma before the hostapi (typically ALSA on Ubuntu).

The voice interaction works as follows: - The user speaks, which leads to the VoiceActivityDetection model activation. - [Optional] the recording pipeline (containing other models like OpenWakeWord) runs checks. - The recording starts. - The recording continues until the user stops talking (based on silence grace period). - The recording is transcribed and sent to the system. - The Agent receives text data to be played to the user. - The playback begins. - The playback can be interrupted by user speaking: - if there is additional recording pipeline the playback will pause while the user speaks (and continue, if the pipeline returns false). - otherwise the new recording will be send to the system, and transcription will stop the playback.

Implementations

ROS based implementation is available in ROS2S2SAgent.

ROS2S2SAgent class definition

rai_s2s.s2s.agents.ros2s2s_agent.ROS2S2SAgent

Bases: SpeechToSpeechAgent

Source code in rai_s2s/s2s/agents/ros2s2s_agent.py
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
class ROS2S2SAgent(SpeechToSpeechAgent):
    def __init__(
        self,
        from_human_topic: str,
        to_human_topic: str,
        *,
        microphone_config: SoundDeviceConfig,
        speaker_config: SoundDeviceConfig,
        transcription_model: BaseTranscriptionModel,
        vad: BaseVoiceDetectionModel,
        tts: TTSModel,
        grace_period: float = 1,
        logger: Optional[logging.Logger] = None,
        **kwargs,
    ):
        super().__init__(
            from_human_topic,
            to_human_topic,
            microphone_config=microphone_config,
            speaker_config=speaker_config,
            transcription_model=transcription_model,
            vad=vad,
            tts=tts,
            grace_period=grace_period,
            logger=logger,
            **kwargs,
        )

    def _setup_hri_connector(self):
        hri_connector = ROS2HRIConnector()
        hri_connector.register_callback(self.to_human_topic, self._on_to_human_message)
        return hri_connector

    def _send_from_human_message(self, data: str):
        print(f"Sending message to {self.from_human_topic}")
        self.hri_connector.send_message(
            ROS2HRIMessage(text=data), self.from_human_topic
        )

    def _send_to_human_message(self, data: str):
        print(f"Sending message to {self.to_human_topic}")
        self.hri_connector.send_message(ROS2HRIMessage(text=data), self.to_human_topic)

See Also

  • Models: For available voice based models and instructions for creating new ones.
  • AutomaticSpeechRecognition: For AutomaticSpeechRecognitionAgent meant for distributed deployment.
  • TextToSpeech: For TextToSpeechAgent meant for distributed deployment.