File size: 34,005 Bytes
9da872f
 
 
 
9a11246
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
07e9e3c
 
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
b713cda
 
 
5ce6940
b713cda
 
 
 
 
5fb657a
20e58a2
 
 
5fb657a
8a5ee8a
 
 
 
5fb657a
9da872f
 
5fb657a
affc41b
 
 
9da872f
8fbc553
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
20e58a2
07e9e3c
 
 
 
 
 
9da872f
f45ab72
 
 
 
9da872f
 
 
 
 
 
07e9e3c
9da872f
 
 
 
 
 
 
07e9e3c
 
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
579082f
9da872f
 
 
 
 
 
 
 
741db5c
 
d29db4b
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
741db5c
579082f
9da872f
 
 
 
 
 
 
300b49f
9da872f
0598343
5fb657a
afdb99d
0598343
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
06a6f96
9da872f
 
 
 
 
 
 
 
06a6f96
9da872f
 
 
 
 
 
 
 
 
6ed5b09
 
 
 
06a6f96
9da872f
06a6f96
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
8a5ee8a
 
5fb657a
8a5ee8a
 
 
5fb657a
 
8a5ee8a
 
 
 
5fb657a
8a5ee8a
 
 
 
 
 
 
 
9da872f
afdb99d
5fb657a
5ce6940
afdb99d
9da872f
 
 
 
 
 
 
5ce6940
 
 
9da872f
 
 
d84e937
 
 
8a5ee8a
 
5fb657a
9da872f
8a5ee8a
5fb657a
8a5ee8a
 
 
9da872f
 
 
0832ea3
9da872f
3f1b696
20e58a2
5fb657a
20e58a2
 
3f1b696
20e58a2
 
3f1b696
 
20e58a2
 
 
 
 
3f1b696
9da872f
0598343
9da872f
 
 
 
 
 
 
 
 
0598343
 
 
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
feebc51
ab1716f
9da872f
 
 
 
feebc51
ab1716f
9da872f
 
0598343
5fb657a
afdb99d
0598343
9da872f
 
5fb657a
afdb99d
eb57938
 
20e58a2
eb57938
3f1b696
 
579082f
eb57938
5fb657a
8689b0f
 
5fb657a
8a5ee8a
 
 
 
 
 
9da872f
5fb657a
afdb99d
affc41b
9da872f
8a5ee8a
9da872f
afdb99d
5ce6940
 
 
5fb657a
9da872f
 
 
afdb99d
 
 
 
 
 
 
 
 
 
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
5ce6940
9da872f
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
d84e937
 
5fb657a
d84e937
 
5fb657a
d84e937
9a11246
 
 
5fb657a
9a11246
 
5fb657a
9a11246
 
d84e937
 
10772b5
d84e937
5fb657a
d84e937
 
 
 
10772b5
d84e937
5fb657a
d84e937
579082f
9a11246
5fb657a
9a11246
 
 
 
 
5fb657a
9a11246
579082f
 
 
 
d84e937
5fb657a
579082f
9a11246
5fb657a
d84e937
 
 
579082f
5fb657a
d84e937
5fb657a
d84e937
 
 
 
5fb657a
 
 
 
d84e937
 
 
5fb657a
d84e937
 
 
 
 
9da872f
58f00d3
0813da7
ae10080
5fb657a
0813da7
 
 
 
 
 
5fb657a
9da872f
 
 
 
58f00d3
 
9da872f
 
 
 
58f00d3
0813da7
 
 
 
 
 
5fb657a
9da872f
 
 
 
58f00d3
 
9da872f
 
 
 
58f00d3
0813da7
 
 
 
 
 
 
5fb657a
0d8fe98
 
 
 
 
 
 
 
9da872f
0d8fe98
9da872f
579082f
0d8fe98
9da872f
 
 
f493f8c
58f00d3
ae10080
 
5fb657a
0813da7
 
 
 
 
 
5fb657a
9da872f
 
 
 
58f00d3
 
9da872f
 
5fb657a
ae10080
 
5fb657a
ae10080
 
 
83f2d5a
ae10080
83f2d5a
ae10080
 
9da872f
 
 
 
 
 
 
58f00d3
 
9da872f
 
 
 
24eb1f8
 
9da872f
 
 
24eb1f8
634577b
 
 
 
 
 
 
 
 
 
 
 
 
5fb657a
 
 
634577b
 
 
f7f01c8
 
 
24eb1f8
634577b
137eac2
24eb1f8
634577b
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
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
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
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
"""Voice satellite protocol for Reachy Mini."""

import hashlib
import logging
import math
import posixpath
import shutil
import time
from collections.abc import Iterable
from typing import Dict, Optional, Set, Union, TYPE_CHECKING
from urllib.parse import urlparse, urlunparse
from urllib.request import urlopen

if TYPE_CHECKING:
    from .camera_server import MJPEGCameraServer

# pylint: disable=no-name-in-module
from aioesphomeapi.api_pb2 import (  # type: ignore[attr-defined]
    ButtonCommandRequest,
    CameraImageRequest,
    DeviceInfoRequest,
    DeviceInfoResponse,
    ListEntitiesDoneResponse,
    ListEntitiesRequest,
    MediaPlayerCommandRequest,
    NumberCommandRequest,
    SelectCommandRequest,
    SubscribeHomeAssistantStatesRequest,
    SubscribeStatesRequest,
    SwitchCommandRequest,
    VoiceAssistantAnnounceFinished,
    VoiceAssistantAnnounceRequest,
    VoiceAssistantAudio,
    VoiceAssistantConfigurationRequest,
    VoiceAssistantConfigurationResponse,
    VoiceAssistantEventResponse,
    VoiceAssistantExternalWakeWord,
    VoiceAssistantRequest,
    VoiceAssistantSetConfiguration,
    VoiceAssistantTimerEventResponse,
    VoiceAssistantWakeWord,
)
from aioesphomeapi.model import (
    VoiceAssistantEventType,
    VoiceAssistantFeature,
    VoiceAssistantTimerEventType,
)
from google.protobuf import message
from pymicro_wakeword import MicroWakeWord
from pyopen_wakeword import OpenWakeWord

from .api_server import APIServer
from .entity import MediaPlayerEntity
from .entity_registry import EntityRegistry, get_entity_key
from .models import AvailableWakeWord, ServerState, WakeWordType
from .util import call_all
from .reachy_controller import ReachyController

_LOGGER = logging.getLogger(__name__)


class VoiceSatelliteProtocol(APIServer):
    """Voice satellite protocol handler for ESPHome."""

    def __init__(self, state: ServerState, camera_server: Optional["MJPEGCameraServer"] = None) -> None:
        super().__init__(state.name)
        self.state = state
        self.state.satellite = self
        self.camera_server = camera_server

        # Initialize streaming state early (before entity setup)
        # This is needed because audio processing thread checks this attribute
        self._is_streaming_audio = False
        self._in_pipeline = False  # True when voice pipeline is active (listening/processing/speaking)
        self._tts_url: Optional[str] = None
        self._tts_played = False
        self._continue_conversation = False
        self._timer_finished = False
        self._external_wake_words: Dict[str, VoiceAssistantExternalWakeWord] = {}

        # Tap-to-talk continuous conversation mode (REMOVED - too many false triggers)
        # Continuous conversation is now controlled via Home Assistant switch
        # self._tap_conversation_mode = False

        # Conversation tracking for continuous conversation
        self._conversation_id: Optional[str] = None
        self._conversation_timeout = 300.0  # 5 minutes, same as ESPHome default
        self._last_conversation_time = 0.0

        # Initialize Reachy controller
        self.reachy_controller = ReachyController(state.reachy_mini)

        # Connect MovementManager to ReachyController for pose control from HA
        if state.motion is not None and state.motion.movement_manager is not None:
            self.reachy_controller.set_movement_manager(state.motion.movement_manager)

            # Setup speech sway callback for audio-driven head motion
            def sway_callback(sway: dict) -> None:
                mm = state.motion.movement_manager
                if mm is not None:
                    mm.set_speech_sway(
                        sway.get("x_m", 0.0),
                        sway.get("y_m", 0.0),
                        sway.get("z_m", 0.0),
                        sway.get("roll_rad", 0.0),
                        sway.get("pitch_rad", 0.0),
                        sway.get("yaw_rad", 0.0),
                    )

            state.tts_player.set_sway_callback(sway_callback)
            _LOGGER.info("Speech sway callback configured for TTS player")

        # Initialize entity registry
        self._entity_registry = EntityRegistry(
            server=self,
            reachy_controller=self.reachy_controller,
            camera_server=camera_server,
            play_emotion_callback=self._play_emotion,
        )

        # Connect gesture state callback
        if camera_server:
            camera_server.set_gesture_state_callback(self._entity_registry.update_gesture_state)

        # Only setup entities once (check if already initialized)
        # This prevents duplicate entity registration on reconnection
        if not getattr(self.state, '_entities_initialized', False):
            if self.state.media_player_entity is None:
                self.state.media_player_entity = MediaPlayerEntity(
                    server=self,
                    key=get_entity_key("reachy_mini_media_player"),
                    name="Media Player",
                    object_id="reachy_mini_media_player",
                    music_player=state.music_player,
                    announce_player=state.tts_player,
                )
                self.state.entities.append(self.state.media_player_entity)

            # Setup all entities using the registry
            self._entity_registry.setup_all_entities(self.state.entities)

            # Mark entities as initialized
            self.state._entities_initialized = True
            _LOGGER.info("Entities initialized: %d total", len(self.state.entities))
        else:
            _LOGGER.debug("Entities already initialized, skipping setup")
            # Update server reference in existing entities
            for entity in self.state.entities:
                entity.server = self

    def handle_voice_event(

        self, event_type: VoiceAssistantEventType, data: Dict[str, str]

    ) -> None:
        _LOGGER.debug("Voice event: type=%s, data=%s", event_type.name, data)

        if event_type == VoiceAssistantEventType.VOICE_ASSISTANT_RUN_START:
            self._tts_url = data.get("url")
            self._tts_played = False
            self._continue_conversation = False
            # Reachy Mini: Start listening animation
            self._reachy_on_listening()

            # Note: TTS URL requires HA authentication, cannot pre-download
            # Speaking animation uses JSON-defined multi-frequency sway instead

        elif event_type in (
            VoiceAssistantEventType.VOICE_ASSISTANT_STT_VAD_END,
            VoiceAssistantEventType.VOICE_ASSISTANT_STT_END,
        ):
            self._is_streaming_audio = False
            # Reachy Mini: Stop listening, start thinking
            self._reachy_on_thinking()

        elif event_type == VoiceAssistantEventType.VOICE_ASSISTANT_INTENT_PROGRESS:
            if data.get("tts_start_streaming") == "1":
                # Start streaming early
                self.play_tts()

        elif event_type == VoiceAssistantEventType.VOICE_ASSISTANT_INTENT_END:
            if data.get("continue_conversation") == "1":
                self._continue_conversation = True

        elif event_type == VoiceAssistantEventType.VOICE_ASSISTANT_TTS_START:
            # Reachy Mini: Start speaking animation (JSON-defined multi-frequency sway)
            _LOGGER.debug("TTS_START event received, triggering speaking animation")
            self._reachy_on_speaking()

        elif event_type == VoiceAssistantEventType.VOICE_ASSISTANT_TTS_END:
            self._tts_url = data.get("url")
            self.play_tts()

        elif event_type == VoiceAssistantEventType.VOICE_ASSISTANT_RUN_END:
            # Pipeline run ended
            self._tts_played = False
            self._is_streaming_audio = False

            # Check if should continue conversation
            self._handle_run_end()

    def handle_timer_event(

        self,

        event_type: VoiceAssistantTimerEventType,

        msg: VoiceAssistantTimerEventResponse,

    ) -> None:
        _LOGGER.debug("Timer event: type=%s", event_type.name)

        if event_type == VoiceAssistantTimerEventType.VOICE_ASSISTANT_TIMER_FINISHED:
            if not self._timer_finished:
                self.state.active_wake_words.add(self.state.stop_word.id)
                self._timer_finished = True
                self.duck()
                self._play_timer_finished()
                # Reachy Mini: Timer finished animation
                self._reachy_on_timer_finished()

    def handle_message(self, msg: message.Message) -> Iterable[message.Message]:
        if isinstance(msg, VoiceAssistantEventResponse):
            # Pipeline event
            data: Dict[str, str] = {}
            for arg in msg.data:
                data[arg.name] = arg.value
            self.handle_voice_event(VoiceAssistantEventType(msg.event_type), data)

        elif isinstance(msg, VoiceAssistantAnnounceRequest):
            _LOGGER.debug("Announcing: %s", msg.text)
            assert self.state.media_player_entity is not None

            urls = []
            if msg.preannounce_media_id:
                urls.append(msg.preannounce_media_id)
            urls.append(msg.media_id)

            self.state.active_wake_words.add(self.state.stop_word.id)
            self._continue_conversation = msg.start_conversation
            self.duck()

            yield from self.state.media_player_entity.play(
                urls, announcement=True, done_callback=self._tts_finished
            )

        elif isinstance(msg, VoiceAssistantTimerEventResponse):
            self.handle_timer_event(VoiceAssistantTimerEventType(msg.event_type), msg)

        elif isinstance(msg, DeviceInfoRequest):
            yield DeviceInfoResponse(
                uses_password=False,
                name=self.state.name,
                mac_address=self.state.mac_address,
                voice_assistant_feature_flags=(
                    VoiceAssistantFeature.VOICE_ASSISTANT
                    | VoiceAssistantFeature.API_AUDIO
                    | VoiceAssistantFeature.ANNOUNCE
                    | VoiceAssistantFeature.START_CONVERSATION
                    | VoiceAssistantFeature.TIMERS
                ),
            )

        elif isinstance(
            msg,
            (
                ListEntitiesRequest,
                SubscribeHomeAssistantStatesRequest,
                SubscribeStatesRequest,
                MediaPlayerCommandRequest,
                NumberCommandRequest,
                SwitchCommandRequest,
                SelectCommandRequest,
                ButtonCommandRequest,
                CameraImageRequest,
            ),
        ):
            for entity in self.state.entities:
                yield from entity.handle_message(msg)

            if isinstance(msg, ListEntitiesRequest):
                yield ListEntitiesDoneResponse()

        elif isinstance(msg, VoiceAssistantConfigurationRequest):
            available_wake_words = [
                VoiceAssistantWakeWord(
                    id=ww.id,
                    wake_word=ww.wake_word,
                    trained_languages=ww.trained_languages,
                )
                for ww in self.state.available_wake_words.values()
            ]

            for eww in msg.external_wake_words:
                if eww.model_type != "micro":
                    continue

                available_wake_words.append(
                    VoiceAssistantWakeWord(
                        id=eww.id,
                        wake_word=eww.wake_word,
                        trained_languages=eww.trained_languages,
                    )
                )
                self._external_wake_words[eww.id] = eww

            yield VoiceAssistantConfigurationResponse(
                available_wake_words=available_wake_words,
                active_wake_words=[
                    ww.id
                    for ww in self.state.wake_words.values()
                    if ww.id in self.state.active_wake_words
                ],
                max_active_wake_words=2,
            )

            _LOGGER.info("Connected to Home Assistant")

        elif isinstance(msg, VoiceAssistantSetConfiguration):
            # Change active wake words
            active_wake_words: Set[str] = set()

            for wake_word_id in msg.active_wake_words:
                if wake_word_id in self.state.wake_words:
                    # Already loaded, just add to active set
                    active_wake_words.add(wake_word_id)
                    continue

                model_info = self.state.available_wake_words.get(wake_word_id)
                if not model_info:
                    # Check external wake words (may require download)
                    external_wake_word = self._external_wake_words.get(wake_word_id)
                    if not external_wake_word:
                        _LOGGER.warning("Wake word not found: %s", wake_word_id)
                        continue

                    model_info = self._download_external_wake_word(external_wake_word)
                    if not model_info:
                        continue

                    self.state.available_wake_words[wake_word_id] = model_info

                _LOGGER.debug("Loading wake word: %s", model_info.wake_word_path)
                loaded_model = model_info.load()
                # Set id attribute on the model for later identification
                setattr(loaded_model, 'id', wake_word_id)
                self.state.wake_words[wake_word_id] = loaded_model
                _LOGGER.info("Wake word loaded: %s", wake_word_id)
                active_wake_words.add(wake_word_id)
                # Don't break - load ALL requested wake words, not just the first one

            self.state.active_wake_words = active_wake_words
            _LOGGER.debug("Active wake words: %s", active_wake_words)

            self.state.preferences.active_wake_words = list(active_wake_words)
            self.state.save_preferences()
            self.state.wake_words_changed = True

    def handle_audio(self, audio_chunk: bytes) -> None:
        if not self._is_streaming_audio:
            return
        self.send_messages([VoiceAssistantAudio(data=audio_chunk)])

    def _get_or_create_conversation_id(self) -> str:
        """Get existing conversation_id or create a new one.



        Reuses conversation_id if within timeout period, otherwise creates new one.

        """
        now = time.time()
        if (self._conversation_id is None or
                now - self._last_conversation_time > self._conversation_timeout):
            # Create new conversation_id
            import uuid
            self._conversation_id = str(uuid.uuid4())
            _LOGGER.debug("Created new conversation_id: %s", self._conversation_id)

        self._last_conversation_time = now
        return self._conversation_id

    def _clear_conversation(self) -> None:
        """Clear conversation state when exiting conversation mode."""
        self._conversation_id = None
        self._continue_conversation = False

    def wakeup(self, wake_word: Union[MicroWakeWord, OpenWakeWord]) -> None:
        """Handle wake word detection - start voice pipeline.



        Only called when in idle state (checked by voice_assistant.py).

        """
        if self._timer_finished:
            # Stop timer instead
            self._timer_finished = False
            self.state.tts_player.stop()
            _LOGGER.debug("Stopping timer finished sound")
            return

        # Mark pipeline as active
        self._in_pipeline = True
        
        wake_word_phrase = wake_word.wake_word
        _LOGGER.debug("Detected wake word: %s", wake_word_phrase)

        # Turn toward sound source using DOA (Direction of Arrival)
        self._turn_to_sound_source()

        # Get or create conversation_id for context tracking
        conv_id = self._get_or_create_conversation_id()

        self.send_messages(
            [VoiceAssistantRequest(
                start=True,
                wake_word_phrase=wake_word_phrase,
                conversation_id=conv_id,
            )]
        )
        self.duck()
        self._is_streaming_audio = True
        self.state.tts_player.play(self.state.wakeup_sound)

    def wakeup_from_tap(self) -> None:
        """Trigger wake-up from tap detection.



        NOTE: This method is DISABLED. Tap-to-wake caused too many false triggers.

        Continuous conversation is now controlled via Home Assistant switch.

        """
        _LOGGER.warning("wakeup_from_tap() called but tap wake is disabled")
        return

    def is_tap_conversation_active(self) -> bool:
        """Check if tap-triggered continuous conversation is active.



        NOTE: Tap wake is DISABLED. This always returns False.

        """
        return False

    def stop(self) -> None:
        """Stop current TTS playback (e.g., user said stop word)."""
        self.state.active_wake_words.discard(self.state.stop_word.id)
        self.state.tts_player.stop()

        if self._timer_finished:
            self._timer_finished = False
            _LOGGER.debug("Stopping timer finished sound")
        else:
            _LOGGER.debug("TTS response stopped manually")

        # Send announce finished to HA
        self.send_messages([VoiceAssistantAnnounceFinished()])
        # Note: RUN_END event will handle the rest

    def play_tts(self) -> None:
        if (not self._tts_url) or self._tts_played:
            return

        self._tts_played = True
        _LOGGER.debug("Playing TTS response: %s", self._tts_url)

        self.state.active_wake_words.add(self.state.stop_word.id)
        self.state.tts_player.play(self._tts_url, done_callback=self._tts_finished)

    def duck(self) -> None:
        _LOGGER.debug("Ducking music")
        self.state.music_player.duck()
        # Pause Sendspin to prevent audio conflicts during voice interaction
        self.state.music_player.pause_sendspin()

    def unduck(self) -> None:
        _LOGGER.debug("Unducking music")
        self.state.music_player.unduck()
        # Resume Sendspin audio
        self.state.music_player.resume_sendspin()

    def _tts_finished(self) -> None:
        """Called when TTS audio playback finishes.



        Following reference project pattern: handle continue conversation here.

        """
        self.state.active_wake_words.discard(self.state.stop_word.id)
        self.send_messages([VoiceAssistantAnnounceFinished()])

        # Check if should continue conversation
        # 1. Our switch is ON: Always continue (unconditional)
        # 2. Our switch is OFF: Follow HA's continue_conversation request
        continuous_mode = self.state.preferences.continuous_conversation
        should_continue = continuous_mode or self._continue_conversation

        if should_continue:
            _LOGGER.debug("Continuing conversation (our_switch=%s, ha_request=%s)",
                         continuous_mode, self._continue_conversation)

            # Play prompt sound to indicate ready for next input
            self.state.tts_player.play(self.state.wakeup_sound)

            # Use same conversation_id for context continuity
            conv_id = self._get_or_create_conversation_id()
            self.send_messages([VoiceAssistantRequest(
                start=True,
                conversation_id=conv_id,
            )])
            self._is_streaming_audio = True

            # Stay in listening mode
            self._reachy_on_listening()
        else:
            self._clear_conversation()
            self.unduck()
            _LOGGER.debug("Conversation finished")
            
            # Mark pipeline as inactive - ready for new wake word
            self._in_pipeline = False

            # Reachy Mini: Return to idle
            self._reachy_on_idle()

    def _handle_run_end(self) -> None:
        """Handle pipeline RUN_END event.



        Following reference project pattern: call _tts_finished if TTS wasn't played.

        """
        if not self._tts_played:
            self._tts_finished()

        self._tts_played = False

    def _play_timer_finished(self) -> None:
        if not self._timer_finished:
            self.unduck()
            return

        self.state.tts_player.play(
            self.state.timer_finished_sound,
            done_callback=lambda: call_all(
                lambda: time.sleep(1.0), self._play_timer_finished
            ),
        )

    def connection_lost(self, exc):
        super().connection_lost(exc)
        _LOGGER.info("Disconnected from Home Assistant")
        # Clear streaming state on disconnect
        self._is_streaming_audio = False
        self._in_pipeline = False
        self._tts_url = None
        self._tts_played = False
        self._continue_conversation = False

    def _download_external_wake_word(

        self, external_wake_word: VoiceAssistantExternalWakeWord

    ) -> Optional[AvailableWakeWord]:
        eww_dir = self.state.download_dir / "external_wake_words"
        eww_dir.mkdir(parents=True, exist_ok=True)

        config_path = eww_dir / f"{external_wake_word.id}.json"
        should_download_config = not config_path.exists()

        # Check if we need to download the model file
        model_path = eww_dir / f"{external_wake_word.id}.tflite"
        should_download_model = True

        if model_path.exists():
            model_size = model_path.stat().st_size
            if model_size == external_wake_word.model_size:
                with open(model_path, "rb") as model_file:
                    model_hash = hashlib.sha256(model_file.read()).hexdigest()

                if model_hash == external_wake_word.model_hash:
                    should_download_model = False
                    _LOGGER.debug(
                        "Model size and hash match for %s. Skipping download.",
                        external_wake_word.id,
                    )

        if should_download_config or should_download_model:
            # Download config
            _LOGGER.debug("Downloading %s to %s", external_wake_word.url, config_path)
            with urlopen(external_wake_word.url) as request:
                if request.status != 200:
                    _LOGGER.warning(
                        "Failed to download: %s, status=%s",
                        external_wake_word.url,
                        request.status,
                    )
                    return None

                with open(config_path, "wb") as model_file:
                    shutil.copyfileobj(request, model_file)

        if should_download_model:
            # Download model file
            parsed_url = urlparse(external_wake_word.url)
            parsed_url = parsed_url._replace(
                path=posixpath.join(posixpath.dirname(parsed_url.path), model_path.name)
            )
            model_url = urlunparse(parsed_url)

            _LOGGER.debug("Downloading %s to %s", model_url, model_path)
            with urlopen(model_url) as request:
                if request.status != 200:
                    _LOGGER.warning(
                        "Failed to download: %s, status=%s", model_url, request.status
                    )
                    return None

                with open(model_path, "wb") as model_file:
                    shutil.copyfileobj(request, model_file)

        return AvailableWakeWord(
            id=external_wake_word.id,
            type=WakeWordType.MICRO_WAKE_WORD,
            wake_word=external_wake_word.wake_word,
            trained_languages=external_wake_word.trained_languages,
            wake_word_path=config_path,
        )

    # -------------------------------------------------------------------------
    # Reachy Mini Motion Control
    # -------------------------------------------------------------------------

    def _turn_to_sound_source(self) -> None:
        """Turn robot head toward sound source using DOA at wakeup.



        This is called once at wakeup to orient the robot toward the speaker.

        Face tracking will take over after the initial turn.



        DOA angle convention (from SDK):

        - 0 radians = left (Y+ direction in head frame)

        - π/2 radians = front (X+ direction in head frame)

        - π radians = right (Y- direction in head frame)



        The SDK uses: p_head = [sin(doa), cos(doa), 0]

        So we need to convert this to yaw angle.



        Note: We don't check speech_detected because by the time wake word

        detection completes, the user may have stopped speaking.

        """
        if not self.state.motion_enabled or not self.state.reachy_mini:
            _LOGGER.info("DOA turn-to-sound: motion disabled or no robot")
            return

        try:
            # Get DOA from reachy_controller (only read once)
            doa = self.reachy_controller.get_doa_angle()
            if doa is None:
                _LOGGER.info("DOA not available, skipping turn-to-sound")
                return

            angle_rad, speech_detected = doa
            _LOGGER.debug("DOA raw: angle=%.3f rad (%.1f°), speech=%s",
                         angle_rad, math.degrees(angle_rad), speech_detected)

            # Convert DOA to direction vector in head frame
            # SDK convention: p_head = [sin(doa), cos(doa), 0]
            # where X+ is front, Y+ is left
            dir_x = math.sin(angle_rad)  # Front component
            dir_y = math.cos(angle_rad)  # Left component

            # Calculate yaw angle from direction vector
            # DOA convention: 0 = left, π/2 = front, π = right
            # Robot yaw: positive = turn left, negative = turn right
            # yaw = doa - π/2 maps: left(0) → -90°, front(π/2) → 0°, right(π) → +90°
            yaw_rad = angle_rad - math.pi / 2
            yaw_deg = math.degrees(yaw_rad)

            _LOGGER.debug("DOA direction: x=%.2f, y=%.2f, yaw=%.1f°",
                         dir_x, dir_y, yaw_deg)

            # Only turn if angle is significant (> 10°) to avoid noise
            DOA_THRESHOLD_DEG = 10.0
            if abs(yaw_deg) < DOA_THRESHOLD_DEG:
                _LOGGER.debug("DOA angle %.1f° below threshold (%.1f°), skipping turn",
                             yaw_deg, DOA_THRESHOLD_DEG)
                return

            # Apply 80% of DOA angle as conservative strategy
            # This accounts for potential DOA inaccuracy
            DOA_SCALE = 0.8
            target_yaw_deg = yaw_deg * DOA_SCALE

            _LOGGER.info("Turning toward sound source: DOA=%.1f°, target=%.1f°",
                         yaw_deg, target_yaw_deg)

            # Use MovementManager to turn (non-blocking)
            if self.state.motion and self.state.motion.movement_manager:
                self.state.motion.movement_manager.turn_to_angle(
                    target_yaw_deg,
                    duration=0.5  # Quick turn
                )
        except Exception as e:
            _LOGGER.error("Error in turn-to-sound: %s", e)

    def _reachy_on_listening(self) -> None:
        """Called when listening for speech (HA state: Listening)."""
        # Enable high-frequency face tracking during listening
        self._set_conversation_mode(True)

        # Resume face tracking (may have been paused during speaking)
        if self.camera_server is not None:
            try:
                self.camera_server.set_face_tracking_enabled(True)
            except Exception as e:
                _LOGGER.debug("Failed to resume face tracking: %s", e)

        if not self.state.motion_enabled or not self.state.reachy_mini:
            return
        try:
            _LOGGER.debug("Reachy Mini: Listening animation")
            if self.state.motion:
                self.state.motion.on_listening()
        except Exception as e:
            _LOGGER.error("Reachy Mini motion error: %s", e)

    def _reachy_on_thinking(self) -> None:
        """Called when processing speech (HA state: Processing)."""
        # Resume face tracking (may have been paused during speaking)
        if self.camera_server is not None:
            try:
                self.camera_server.set_face_tracking_enabled(True)
            except Exception as e:
                _LOGGER.debug("Failed to resume face tracking: %s", e)

        if not self.state.motion_enabled or not self.state.reachy_mini:
            return
        try:
            _LOGGER.debug("Reachy Mini: Thinking animation")
            if self.state.motion:
                self.state.motion.on_thinking()
        except Exception as e:
            _LOGGER.error("Reachy Mini motion error: %s", e)

    def _reachy_on_speaking(self) -> None:
        """Called when TTS is playing (HA state: Responding)."""
        # Pause face tracking during speaking - robot will use speaking animation instead
        if self.camera_server is not None:
            try:
                self.camera_server.set_face_tracking_enabled(False)
                _LOGGER.debug("Face tracking paused during speaking")
            except Exception as e:
                _LOGGER.debug("Failed to pause face tracking: %s", e)

        if not self.state.motion_enabled:
            _LOGGER.warning("Motion disabled, skipping speaking animation")
            return
        if not self.state.reachy_mini:
            _LOGGER.warning("No reachy_mini instance, skipping speaking animation")
            return
        if not self.state.motion:
            _LOGGER.warning("No motion controller, skipping speaking animation")
            return

        try:
            _LOGGER.debug("Reachy Mini: Starting speaking animation")
            self.state.motion.on_speaking_start()
        except Exception as e:
            _LOGGER.error("Reachy Mini motion error: %s", e)

    def _reachy_on_idle(self) -> None:
        """Called when returning to idle state (HA state: Idle)."""
        # Disable high-frequency face tracking, switch to adaptive mode
        self._set_conversation_mode(False)

        # Resume face tracking (may have been paused during speaking)
        if self.camera_server is not None:
            try:
                self.camera_server.set_face_tracking_enabled(True)
            except Exception as e:
                _LOGGER.debug("Failed to resume face tracking: %s", e)

        if not self.state.motion_enabled or not self.state.reachy_mini:
            return
        try:
            _LOGGER.debug("Reachy Mini: Idle animation")
            if self.state.motion:
                self.state.motion.on_idle()
        except Exception as e:
            _LOGGER.error("Reachy Mini motion error: %s", e)

    def _set_conversation_mode(self, in_conversation: bool) -> None:
        """Set conversation mode for adaptive face tracking.



        When in conversation, face tracking runs at high frequency.

        When idle, face tracking uses adaptive rate to save CPU.

        """
        if self.camera_server is not None:
            try:
                self.camera_server.set_conversation_mode(in_conversation)
            except Exception as e:
                _LOGGER.debug("Failed to set conversation mode: %s", e)

    def _reachy_on_timer_finished(self) -> None:
        """Called when a timer finishes."""
        if not self.state.motion_enabled or not self.state.reachy_mini:
            return
        try:
            _LOGGER.debug("Reachy Mini: Timer finished animation")
            if self.state.motion:
                self.state.motion.on_timer_finished()
        except Exception as e:
            _LOGGER.error("Reachy Mini motion error: %s", e)

    def _play_emotion(self, emotion_name: str) -> None:
        """Play an emotion/expression from the emotions library.



        Args:

            emotion_name: Name of the emotion (e.g., "happy1", "sad1", etc.)

        """
        try:
            import requests

            # Get WLAN IP from daemon status
            wlan_ip = "localhost"
            if self.state.reachy_mini is not None:
                try:
                    status = self.state.reachy_mini.client.get_status(wait=False)
                    wlan_ip = status.get('wlan_ip', 'localhost')
                except Exception:
                    wlan_ip = "localhost"

            # Call the emotion playback API
            # Dataset: pollen-robotics/reachy-mini-emotions-library
            base_url = f"http://{wlan_ip}:8000/api/move/play/recorded-move-dataset"
            dataset = "pollen-robotics/reachy-mini-emotions-library"
            url = f"{base_url}/{dataset}/{emotion_name}"

            response = requests.post(url, timeout=5)
            if response.status_code == 200:
                result = response.json()
                move_uuid = result.get('uuid')
                _LOGGER.info(f"Playing emotion: {emotion_name} (uuid={move_uuid})")
            else:
                _LOGGER.warning(f"Failed to play emotion {emotion_name}: HTTP {response.status_code}")

        except Exception as e:
            _LOGGER.error(f"Error playing emotion {emotion_name}: {e}")