2026年2月14日 星期六

[OTTO GO] 幼兒教具版(MQTT)

 

OTTO GO 幼兒教具版(MQTT)使用手冊

1. 產品定位

這是一套給幼兒(約 3–7 歲)使用的編程教具。孩子透過「發送簡單指令」讓 OTTO 在 螢幕表情(TFT)+動作(舵機)+音效(喇叭) 之間做出連動反應,像「真的機器人」在互動。


2. 你需要準備

硬體

  • OTTO GO 主機(含 TFT、4 顆伺服馬達、超音波、I2S 喇叭)

  • USB 線 + 電腦(上傳程式用)

  • Wi-Fi 網路環境(OTTO 會連上家裡/教室 Wi-Fi)

軟體

  • Arduino IDE

  • 必裝函式庫:

    • PubSubClient

    • Adafruit GFX

    • Adafruit ST7735 and ST7789

    • ESP32Servo


3. 連線流程(開機到可用)

  1. 上電後打開序列監控視窗(115200)

  2. 成功會看到類似訊息:

  • WiFi OK IP=...

  • MQTT connecting... OK

  • 印出 Topics(CMD/ACK/STATUS)

  1. 使用手機/電腦的 MQTT 客戶端(或你自己做的控制介面)發送指令到 CMD topic


4. MQTT Topics 說明

你目前裝置的 topics(以你的輸出為準):

  • CMD(下指令)
    otto_go/OTTO_GO_A1/4A65B7A0/cmd

  • ACK(回覆/完成訊息)
    otto_go/OTTO_GO_A1/4A65B7A0/ack

  • STATUS(狀態回報)
    otto_go/OTTO_GO_A1/4A65B7A0/status

建議操作方式

  • 你只要「送到 CMD」

  • OTTO 會在 ACK 回覆「收到、完成、警告」

  • OTTO 會每 2 秒在 STATUS 回報一次狀態(IP、表情、速度、距離…)


5. 指令格式(很重要)

指令以 key=value 形式,可用 ; 串多個步驟。

範例:

  • 單一:action=happy

  • 多段:servo_speed=fast;action=happy;delay=300;spk=beep


6. 幼兒版「積木指令」總表(推薦教學用)

這些是最適合孩子的「一塊積木一個指令」。

6.1 action(最推薦:表情+動作+音效一次到位)

送到 CMD:

  • action=happy:笑臉+搖動+張嘴+吼叫

  • action=angry:生氣臉+抖動+嗶嗶

  • action=sleepy:想睡臉+慢動作+提示音

  • action=neutral:回到待機表情/姿勢

6.2 expr(只改表情)

  • expr=happy

  • expr=angry

  • expr=sleepy

  • expr=neutral

  • expr=mouth_open

  • expr=mouth_close

6.3 spk(只播放音效)

  • spk=beep

  • spk=roar

6.4 servo_speed(動作速度)

先設定再做 action/servo 動作:

  • servo_speed=slow

  • servo_speed=normal

  • servo_speed=fast

6.5 ultra(超音波互動開關)

靠近會自動打招呼(happy),可開關:

  • ultra=on

  • ultra=off


7. 老師模式:script(一次下多步)

用法

把多個 token 用 ; 串起來,送到 CMD:

範例 1:表演一段「開心 → 嗶嗶 → 睡覺」

script=servo_speed=fast;action=happy;delay=300;spk=beep;delay=200;expr=sleepy

範例 2:關閉超音波,做一段固定流程

script=ultra=off;expr=happy;spk=roar;delay=300;action=neutral

script 支援 token 清單

  • action=happy|angry|sleepy|neutral

  • expr=happy|angry|sleepy|neutral|mouth_open|mouth_close

  • spk=beep|roar

  • servo_speed=slow|normal|fast

  • servo_all=角度servo_all=角度,時間ms

  • delay=ms

  • ultra=on|off

內建安全限制(避免孩子亂設導致卡死)

  • 最多 24 步

  • delay 最大 2000ms

  • servo_all 會套用安全角度範圍(避免卡住/翻倒)


8. STATUS(狀態回報)看什麼

每 2 秒會回報一包 JSON(示意):

{ "ip":"192.168.1.112", "expr":"happy", "speed":"fast", "ultra":1, "dist":18, "last":"action=happy" }

你可以用它做:

  • 儀表板(目前表情/距離/速度)

  • 課堂評量(孩子是否成功讓機器人變表情)

  • 互動遊戲(距離小於 20cm 自動打招呼)


9. 教學活動建議(幼兒教具版)

活動 A:情緒辨識+編程

  • 老師出情境:「今天很開心/生氣/想睡覺」

  • 孩子選一塊積木:action=happy/angry/sleepy

  • OTTO 用表情+聲音回應,孩子更有「機器人有情緒」的感覺

活動 B:速度概念(快/慢)

  • 先下:servo_speed=slowaction=happy

  • 再下:servo_speed=fastaction=happy

  • 讓孩子比較差異:速度影響機器人「情緒表達」

活動 C:靠近互動(社交距離)

  • ultra=on

  • 孩子靠近 OTTO,OTTO 自動打招呼(happy)

  • 引導孩子理解「感測器」「距離」


10. 常見問題排除

Q1:螢幕背光亮但黑屏

  • 確認你程式中的 TFT 初始化是:

    • SPI.begin(TFT_SCLK, -1, TFT_MOSI, TFT_CS);

    • tft.init(240, 320);

    • tft.setRotation(1);

  • 先跑「RGB 三色測試+Hello」確認硬體正常

Q2:Wi-Fi OK,但 MQTT 連不上

  • Broker host 確認用你成功過的:broker.mqttgo.io

  • Port:1883

  • 確認教室網路沒有擋 1883

Q3:指令送了沒反應

  • topic 是否送到 CMD

  • payload 是否正確(例如 action=happy

  • 看 ACK 是否有回覆 READY / OK / WARN


11. 最小指令清單(給家長/孩子)

只記這 5 個就夠用:

  • action=happy

  • action=angry

  • action=sleepy

  • action=neutral

  • ultra=on / ultra=off


Arduino:

  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
/* 
  OTTO GO 幼兒教具版(MQTT)
  - 表情一定顯示在 TFT(採用你最早可用的 init 流程)
  - 動作/音效/速度控制
  - 超音波互動:靠近自動打招呼(可關閉)
  - 老師模式:script=... 一次多步(內建節流與安全限制)
  - ACK:收到/完成都會回報
  - STATUS:固定週期上報
*/

#include <Arduino.h>
#include <WiFi.h>
#include <PubSubClient.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_ST7789.h>
#include <ESP32Servo.h>
#include "driver/i2s.h"
#include "freertos/semphr.h"

// ===================== Pin map (OTTO GO) =====================
// TFT (SPI)
#define TFT_MOSI 19
#define TFT_SCLK 18
#define TFT_CS    5
#define TFT_DC   16
#define TFT_RST  23

// Ultrasonic
#define US_TRIG 27
#define US_ECHO 39

// Servos
#define SERVO1 21
#define SERVO2 22
#define SERVO3 4
#define SERVO4 14

// Speaker (I2S -> AMP -> SPK white socket)
#define SPK_I2S_LRCK 17
#define SPK_I2S_BCLK 2
#define SPK_I2S_DOUT 32

// ===================== WiFi / MQTT =====================
const char* WIFI_SSID = "ChiYuan";
const char* WIFI_PASS = "22515103";

const char* MQTT_HOST = "mqttgo.io";
const uint16_t MQTT_PORT = 1883;

const char* MQTT_TOPIC_CMD    = "otto_go/OTTO_GO_A1/4A65B7A0/cmd";
const char* MQTT_TOPIC_ACK    = "otto_go/OTTO_GO_A1/4A65B7A0/ack";
const char* MQTT_TOPIC_STATUS = "otto_go/OTTO_GO_A1/4A65B7A0/status";

// ===================== Objects =====================
WiFiClient wifiClient;
PubSubClient mqtt(wifiClient);

Adafruit_ST7789 tft = Adafruit_ST7789(TFT_CS, TFT_DC, TFT_RST);
Servo s1, s2, s3, s4;

// ===================== Helpers =====================
static inline uint16_t RGB565(uint8_t r, uint8_t g, uint8_t b) {
  return ((r & 0xF8) << 8) | ((g & 0xFC) << 3) | (b >> 3);
}

// ===================== TFT stable init(用你最早可用流程) =====================
void tftInitStable() {
  SPI.begin(TFT_SCLK, -1, TFT_MOSI, TFT_CS);
  tft.init(240, 320);
  tft.setRotation(1);
  tft.setTextWrap(false);
}

void tftHelloTestOnce() {
  tft.fillScreen(ST77XX_RED);   delay(150);
  tft.fillScreen(ST77XX_GREEN); delay(150);
  tft.fillScreen(ST77XX_BLUE);  delay(150);
  tft.fillScreen(ST77XX_BLACK);
  tft.setTextColor(ST77XX_WHITE);
  tft.setTextSize(3);
  tft.setCursor(20, 40);
  tft.print("Hello");
}

void tftClear(uint16_t bg = ST77XX_BLACK) {
  tft.fillScreen(bg);
  tft.setTextWrap(false);
}

// ===================== Servo speed & safe range =====================
// ★先宣告 enum,避免 ServoSpeed 未宣告
enum ServoSpeed : uint8_t { SPD_SLOW = 0, SPD_NORMAL = 1, SPD_FAST = 2 };
ServoSpeed servoSpeed = SPD_NORMAL;

// 幼兒安全角度範圍(依實機調整)
int SAFE_MIN = 70;
int SAFE_MAX = 110;

static inline int clampSafeAngle(int a) {
  a = constrain(a, 0, 180);
  return constrain(a, SAFE_MIN, SAFE_MAX);
}

static inline int servoStepDelayMs(ServoSpeed s);
// ★改名避免任何同名衝突(不要叫 speedToStepDelay)
static inline int servoStepDelayMs(ServoSpeed s) {
  if (s == SPD_FAST) return 6;
  if (s == SPD_SLOW) return 18;
  return 10;
}

int curA1 = 90, curA2 = 90, curA3 = 90, curA4 = 90;

void servoWriteAllSafe(int a) {
  a = clampSafeAngle(a);
  curA1 = curA2 = curA3 = curA4 = a;
  s1.write(a); s2.write(a); s3.write(a); s4.write(a);
}

void servoMoveAllToSafe(int target, int ms) {
  target = clampSafeAngle(target);

  // ★先算 stepDelay 再算 steps(你原本反了)
  int stepDelay = servoStepDelayMs(servoSpeed);
  int steps = max(1, ms / stepDelay);

  float a1 = curA1, a2 = curA2, a3 = curA3, a4 = curA4;
  float d1 = (target - a1) / (float)steps;
  float d2 = (target - a2) / (float)steps;
  float d3 = (target - a3) / (float)steps;
  float d4 = (target - a4) / (float)steps;

  for (int i = 0; i < steps; i++) {
    a1 += d1; a2 += d2; a3 += d3; a4 += d4;
    s1.write((int)a1); s2.write((int)a2); s3.write((int)a3); s4.write((int)a4);
    delay(stepDelay);
  }
  curA1 = curA2 = curA3 = curA4 = target;
}

void servoWiggle(int center = 90, int amp = 12, int times = 2, int perMs = 240) {
  center = clampSafeAngle(center);
  int aL = clampSafeAngle(center - amp);
  int aR = clampSafeAngle(center + amp);
  for (int i = 0; i < times; i++) {
    servoMoveAllToSafe(aL, perMs);
    servoMoveAllToSafe(aR, perMs);
  }
  servoMoveAllToSafe(center, perMs);
}

// ===================== Ultrasonic =====================
long readDistanceCM() {
  digitalWrite(US_TRIG, LOW);
  delayMicroseconds(2);
  digitalWrite(US_TRIG, HIGH);
  delayMicroseconds(10);
  digitalWrite(US_TRIG, LOW);

  unsigned long duration = pulseIn(US_ECHO, HIGH, 30000UL);
  if (duration == 0) return -1;
  return (long)(duration / 58UL);
}

long median3(long a, long b, long c) {
  if (a > b) { long t = a; a = b; b = t; }
  if (b > c) { long t = b; b = c; c = t; }
  if (a > b) { long t = a; a = b; b = t; }
  return b;
}

long readDistanceMedian() {
  long d1 = readDistanceCM();
  long d2 = readDistanceCM();
  long d3 = readDistanceCM();
  return median3(d1, d2, d3);
}

// ===================== I2S Speaker(穩定 TX) =====================
const i2s_port_t I2S_PORT = I2S_NUM_0;
enum I2SMode { MODE_NONE = 0, MODE_SPK = 1 };
static volatile I2SMode curMode = MODE_NONE;
static SemaphoreHandle_t i2sMutex = nullptr;
bool spk_ok = false;

static void lockI2S()   { if (i2sMutex) xSemaphoreTake(i2sMutex, portMAX_DELAY); }
static void unlockI2S() { if (i2sMutex) xSemaphoreGive(i2sMutex); }

static void i2sStopAndUninstallSafe() {
  if (curMode == MODE_NONE) return;
  i2s_stop(I2S_PORT);
  i2s_driver_uninstall(I2S_PORT);
  curMode = MODE_NONE;
}

bool i2sInitSpeaker() {
  i2sStopAndUninstallSafe();

  i2s_config_t cfg = {
    .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_TX),
    .sample_rate = 22050,
    .bits_per_sample = I2S_BITS_PER_SAMPLE_16BIT,
    .channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT,
    .communication_format = I2S_COMM_FORMAT_I2S_MSB,
    .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1,
    .dma_buf_count = 4,
    .dma_buf_len = 128,
    .use_apll = false,
    .tx_desc_auto_clear = true,
    .fixed_mclk = 0
  };

  i2s_pin_config_t pin_cfg = {
    .bck_io_num = SPK_I2S_BCLK,
    .ws_io_num = SPK_I2S_LRCK,
    .data_out_num = SPK_I2S_DOUT,
    .data_in_num = I2S_PIN_NO_CHANGE
  };

  if (i2s_driver_install(I2S_PORT, &cfg, 0, NULL) != ESP_OK) return false;
  if (i2s_set_pin(I2S_PORT, &pin_cfg) != ESP_OK) return false;

  i2s_zero_dma_buffer(I2S_PORT);
  i2s_start(I2S_PORT);
  curMode = MODE_SPK;
  return true;
}

bool ensureSpeakerModeLocked() {
  if (curMode == MODE_SPK) return true;
  spk_ok = i2sInitSpeaker();
  return spk_ok;
}

static uint32_t rng = 1;
static inline int16_t noise16() {
  rng = rng * 1664525UL + 1013904223UL;
  return (int16_t)(rng >> 16);
}

void playBeep1kHz_200ms_locked() {
  if (!ensureSpeakerModeLocked()) return;

  const int sampleRate = 22050;
  const float freq = 1000.0f;
  const float durSec = 0.2f;
  const int total = (int)(sampleRate * durSec);

  const int N = 256;
  int16_t stereo[N * 2];
  float phase = 0.0f;

  for (int i = 0; i < total;) {
    int n = (total - i > N) ? N : (total - i);
    for (int k = 0; k < n; k++) {
      phase += 2.0f * 3.1415926f * freq / (float)sampleRate;
      if (phase > 2.0f * 3.1415926f) phase -= 2.0f * 3.1415926f;
      int16_t v = (int16_t)(sinf(phase) * 12000);
      stereo[2 * k + 0] = v;
      stereo[2 * k + 1] = v;
    }
    size_t written = 0;
    i2s_write(I2S_PORT, (const char*)stereo, n * 2 * sizeof(int16_t), &written, portMAX_DELAY);
    i += n;
  }
}

void playRoarOnce_locked() {
  if (!ensureSpeakerModeLocked()) return;

  const int sampleRate = 22050;
  const float durSec = 0.55f;
  const int total = (int)(sampleRate * durSec);

  const int N = 256;
  int16_t stereo[N * 2];
  float phase = 0.0f;

  for (int i = 0; i < total;) {
    int n = (total - i > N) ? N : (total - i);

    for (int k = 0; k < n; k++) {
      float t = (float)(i + k) / (float)total;
      float f = 130.0f - 60.0f * t;
      phase += 2.0f * 3.1415926f * f / (float)sampleRate;
      if (phase > 2.0f * 3.1415926f) phase -= 2.0f * 3.1415926f;

      float env = (t < 0.08f) ? (t / 0.08f) : (1.0f - (t - 0.08f) / 0.92f);
      if (env < 0) env = 0;

      float s = sinf(phase) * 0.65f + sinf(phase * 0.5f) * 0.35f;
      float nz = (noise16() / 32768.0f) * 0.30f;
      float out = (s + nz) * env;

      int32_t v = (int32_t)(out * 28000.0f);
      v = constrain(v, -32768, 32767);

      int16_t vv = (int16_t)v;
      stereo[2 * k + 0] = vv;
      stereo[2 * k + 1] = vv;
    }

    size_t written = 0;
    i2s_write(I2S_PORT, (const char*)stereo, n * 2 * sizeof(int16_t), &written, portMAX_DELAY);
    i += n;
  }
}

// ===================== TFT 表情庫(簡單幾何) =====================
String currentExpr = "neutral";
bool mouthOpen = false;

void drawEyes(int x1, int y1, int r1, int x2, int y2, int r2, uint16_t c) {
  tft.fillCircle(x1, y1, r1, c);
  tft.fillCircle(x2, y2, r2, c);
}

void drawMouthLine(int x, int y, int w, int h, uint16_t c) {
  tft.fillRoundRect(x, y, w, h, h / 2, c);
}

void showTitle(const char* label) {
  tft.setTextSize(2);
  tft.setTextColor(ST77XX_YELLOW, ST77XX_BLACK);
  tft.setCursor(10, 10);
  tft.print(label);
}

void exprNeutral() {
  tftClear(ST77XX_BLACK);
  drawEyes(90, 80, 18, 150, 80, 18, ST77XX_WHITE);
  drawMouthLine(95, 140, 50, 10, ST77XX_WHITE);
  showTitle("NEUTRAL");
  currentExpr = "neutral";
}

void exprHappy() {
  tftClear(ST77XX_BLACK);
  tft.drawFastHLine(72, 75, 35, ST77XX_WHITE);
  tft.drawFastHLine(132, 75, 35, ST77XX_WHITE);
  tft.drawFastHLine(72, 76, 35, ST77XX_WHITE);
  tft.drawFastHLine(132, 76, 35, ST77XX_WHITE);
  tft.drawCircle(120, 140, 28, ST77XX_WHITE);
  tft.fillRect(60, 112, 120, 28, ST77XX_BLACK);
  showTitle("HAPPY");
  currentExpr = "happy";
}

void exprAngry() {
  tftClear(ST77XX_BLACK);
  tft.drawLine(60, 60, 105, 75, ST77XX_RED);
  tft.drawLine(180, 60, 135, 75, ST77XX_RED);
  drawEyes(90, 85, 16, 150, 85, 16, ST77XX_WHITE);
  drawMouthLine(90, 145, 60, 10, ST77XX_RED);
  showTitle("ANGRY");
  currentExpr = "angry";
}

void exprSleepy() {
  tftClear(ST77XX_BLACK);
  tft.drawFastHLine(70, 85, 40, ST77XX_WHITE);
  tft.drawFastHLine(130, 85, 40, ST77XX_WHITE);
  tft.drawFastHLine(70, 86, 40, ST77XX_WHITE);
  tft.drawFastHLine(130, 86, 40, ST77XX_WHITE);
  drawMouthLine(105, 145, 30, 8, ST77XX_WHITE);

  tft.setTextColor(ST77XX_CYAN, ST77XX_BLACK);
  tft.setTextSize(3);
  tft.setCursor(185, 35); tft.print("Z");
  tft.setTextSize(2);
  tft.setCursor(205, 60); tft.print("Z");

  showTitle("SLEEPY");
  currentExpr = "sleepy";
}

void drawTigerMouth(bool open) {
  int cx = tft.width() / 2;
  int cy = tft.height() / 2;

  uint16_t furLight = RGB565(235, 228, 210);
  uint16_t shadow   = RGB565(160, 150, 135);
  uint16_t lineDark = RGB565(40, 40, 40);
  uint16_t dotDark  = RGB565(70, 70, 70);

  tft.fillScreen(ST77XX_BLACK);

  tft.fillCircle(cx - 55, cy + 10, 55, furLight);
  tft.fillCircle(cx + 55, cy + 10, 55, furLight);
  tft.fillRoundRect(cx - 90, cy - 25, 180, 110, 28, furLight);

  tft.fillRoundRect(cx - 85, cy + 60, 170, 22, 12, shadow);
  tft.fillRoundRect(cx - 40, cy + 55, 80, 10, 5, RGB565(120, 110, 100));

  int dotY1 = cy + 6, dotY2 = cy + 26;
  for (int k = 0; k < 3; k++) {
    tft.fillCircle(cx - 55 - k * 12, dotY1 + k * 2, 2, dotDark);
    tft.fillCircle(cx - 55 - k * 12, dotY2 + k * 2, 2, dotDark);
    tft.fillCircle(cx + 55 + k * 12, dotY1 + k * 2, 2, dotDark);
    tft.fillCircle(cx + 55 + k * 12, dotY2 + k * 2, 2, dotDark);
  }

  tft.drawLine(cx, cy - 5, cx, open ? (cy + 10) : (cy + 20), lineDark);
  tft.drawLine(cx - 1, cy - 5, cx - 1, open ? (cy + 10) : (cy + 20), RGB565(80, 80, 80));

  int mouthY = open ? (cy + 16) : (cy + 18);
  int N = open ? 36 : 34;
  int div = open ? 85 : 95;
  for (int i = 0; i < N; i++) {
    int y = mouthY + (i * i) / div;
    tft.drawPixel(cx - i, y, lineDark);
    tft.drawPixel(cx - i, y + 1, lineDark);
    tft.drawPixel(cx + i, y, lineDark);
    tft.drawPixel(cx + i, y + 1, lineDark);
  }

  tft.fillCircle(cx - (open ? 38 : 36), mouthY + (open ? 14 : 12), 3, lineDark);
  tft.fillCircle(cx + (open ? 38 : 36), mouthY + (open ? 14 : 12), 3, lineDark);

  if (!open) {
    tft.fillRoundRect(cx - 10, mouthY + 20, 20, 4, 2, RGB565(90, 80, 70));
  } else {
    uint16_t mouthIn = RGB565(15, 15, 15);
    uint16_t tongue  = RGB565(210, 120, 120);
    int w = 90, h = 45;
    int x = cx - w / 2, y0 = cy + 28;
    tft.fillRoundRect(x, y0, w, h, 18, mouthIn);
    tft.fillCircle(cx, y0 + h, 22, mouthIn);
    tft.fillRoundRect(cx - 22, y0 + 18, 44, 20, 10, tongue);
    tft.fillCircle(cx, y0 + 36, 14, tongue);
  }

  tft.setTextSize(2);
  tft.setTextColor(ST77XX_YELLOW, ST77XX_BLACK);
  tft.setCursor(10, 10);
  tft.print(open ? "MOUTH: OPEN" : "MOUTH: CLOSE");

  currentExpr = open ? "mouth_open" : "mouth_close";
  mouthOpen = open;
}

void showExpression(const String& name) {
  if (name == "happy") exprHappy();
  else if (name == "angry") exprAngry();
  else if (name == "sleepy") exprSleepy();
  else if (name == "mouth_open") drawTigerMouth(true);
  else if (name == "mouth_close") drawTigerMouth(false);
  else exprNeutral();
}

// ===================== Actions =====================
bool actionRunning = false;

void actionNeutral() {
  showExpression("neutral");
  servoSpeed = SPD_NORMAL;
  servoMoveAllToSafe(90, 280);
}

void actionHappy() {
  showExpression("happy");
  servoSpeed = SPD_FAST;
  servoWiggle(90, 12, 2, 220);
  drawTigerMouth(true);
  lockI2S(); playRoarOnce_locked(); unlockI2S();
  delay(120);
  drawTigerMouth(false);
  showExpression("happy");
}

void actionAngry() {
  showExpression("angry");
  servoSpeed = SPD_FAST;
  servoMoveAllToSafe(105, 220);
  servoMoveAllToSafe(75,  220);
  servoMoveAllToSafe(105, 220);
  lockI2S(); playBeep1kHz_200ms_locked(); unlockI2S();
  delay(80);
  lockI2S(); playBeep1kHz_200ms_locked(); unlockI2S();
}

void actionSleepy() {
  showExpression("sleepy");
  servoSpeed = SPD_SLOW;
  servoMoveAllToSafe(90, 650);
  lockI2S(); playBeep1kHz_200ms_locked(); unlockI2S();
}

void runAction(const String& a) {
  if (actionRunning) return;
  actionRunning = true;

  if (a == "happy") actionHappy();
  else if (a == "angry") actionAngry();
  else if (a == "sleepy") actionSleepy();
  else actionNeutral();

  actionRunning = false;
}

// ===================== MQTT parsing =====================
static String lastCmd = "NONE";
bool ultraEnabled = true;

String getKV(const String& msg, const String& key) {
  int p = msg.indexOf(key + "=");
  if (p < 0) return "";
  int s = p + key.length() + 1;
  int e1 = msg.indexOf(';', s);
  int e2 = msg.indexOf('&', s);
  int e = -1;
  if (e1 >= 0 && e2 >= 0) e = min(e1, e2);
  else if (e1 >= 0) e = e1;
  else if (e2 >= 0) e = e2;
  else e = msg.length();
  return msg.substring(s, e);
}

void mqttPublishAck(const String& s) {
  mqtt.publish(MQTT_TOPIC_ACK, s.c_str());
}

int speedFromName(const String& s) {
  if (s == "slow") return (int)SPD_SLOW;
  if (s == "fast") return (int)SPD_FAST;
  return (int)SPD_NORMAL;
}

String speedName() {
  if (servoSpeed == SPD_SLOW) return "slow";
  if (servoSpeed == SPD_FAST) return "fast";
  return "normal";
}

// ===== script engine =====
void applyOneToken(const String& token);

void runScript(const String& script) {
  mqttPublishAck("OK script=START");
  int count = 0;
  int start = 0;

  while (start < (int)script.length() && count < 24) {
    int sep = script.indexOf(';', start);
    String tok = (sep < 0) ? script.substring(start) : script.substring(start, sep);
    tok.trim();
    if (tok.length()) {
      applyOneToken(tok);
      count++;
    }
    if (sep < 0) break;
    start = sep + 1;
  }

  mqttPublishAck("OK script=DONE");
}

void applyOneToken(const String& token) {
  String t = token;
  t.trim();

  String action = getKV(t, "action");
  if (action.length()) {
    runAction(action);
    mqttPublishAck(String("DONE action=") + action);
    return;
  }

  String expr = getKV(t, "expr");
  if (expr.length()) {
    showExpression(expr);
    mqttPublishAck(String("DONE expr=") + expr);
    return;
  }

  String spk = getKV(t, "spk");
  if (spk.length()) {
    lockI2S();
    if (spk == "roar") playRoarOnce_locked();
    else playBeep1kHz_200ms_locked();
    unlockI2S();
    mqttPublishAck(String("DONE spk=") + spk);
    return;
  }

  String speed = getKV(t, "servo_speed");
  if (speed.length()) {
    servoSpeed = (ServoSpeed)speedFromName(speed);
    mqttPublishAck(String("DONE servo_speed=") + speedName());
    return;
  }

  String sa = getKV(t, "servo_all");
  if (sa.length()) {
    int comma = sa.indexOf(',');
    int ang = 90;
    int ms = 300;
    if (comma < 0) {
      ang = sa.toInt();
    } else {
      ang = sa.substring(0, comma).toInt();
      ms  = sa.substring(comma + 1).toInt();
    }
    ms = constrain(ms, 50, 1200);
    servoMoveAllToSafe(ang, ms);
    mqttPublishAck(String("DONE servo_all=") + String(clampSafeAngle(ang)) + "," + String(ms));
    return;
  }

  String d = getKV(t, "delay");
  if (d.length()) {
    int ms = constrain(d.toInt(), 0, 2000);
    delay(ms);
    mqttPublishAck(String("DONE delay=") + String(ms));
    return;
  }

  String u = getKV(t, "ultra");
  if (u.length()) {
    ultraEnabled = (u == "on");
    mqttPublishAck(String("DONE ultra=") + (ultraEnabled ? "on" : "off"));
    return;
  }

  mqttPublishAck(String("WARN unknown_token=") + t);
}

// ===== main command =====
void applyCommand(const String& msg) {
  lastCmd = msg;

  String script = getKV(msg, "script");
  if (script.length()) {
    runScript(script);
    return;
  }

  String speed = getKV(msg, "servo_speed");
  if (speed.length()) {
    servoSpeed = (ServoSpeed)speedFromName(speed);
    mqttPublishAck(String("OK servo_speed=") + speedName());
  }

  String action = getKV(msg, "action");
  if (action.length()) {
    mqttPublishAck(String("OK action=") + action);
    runAction(action);
    mqttPublishAck(String("DONE action=") + action);
    return;
  }

  String expr = getKV(msg, "expr");
  if (expr.length()) {
    showExpression(expr);
    mqttPublishAck(String("DONE expr=") + expr);
  }

  String spk = getKV(msg, "spk");
  if (spk.length()) {
    lockI2S();
    if (spk == "roar") playRoarOnce_locked();
    else playBeep1kHz_200ms_locked();
    unlockI2S();
    mqttPublishAck(String("DONE spk=") + spk);
  }

  String u = getKV(msg, "ultra");
  if (u.length()) {
    ultraEnabled = (u == "on");
    mqttPublishAck(String("DONE ultra=") + (ultraEnabled ? "on" : "off"));
  }

  if (!script.length() && !action.length() && !expr.length() && !spk.length() && !speed.length() && !u.length()) {
    mqttPublishAck("WARN empty_or_unknown");
  }
}

void mqttCallback(char* topic, byte* payload, unsigned int len) {
  String msg;
  msg.reserve(len + 1);
  for (unsigned int i = 0; i < len; i++) msg += (char)payload[i];
  msg.trim();
  applyCommand(msg);
}

// ===================== WiFi/MQTT connect =====================
void connectWiFi() {
  WiFi.mode(WIFI_STA);
  WiFi.begin(WIFI_SSID, WIFI_PASS);
  Serial.print("WiFi connecting");
  while (WiFi.status() != WL_CONNECTED) {
    delay(300);
    Serial.print(".");
  }
  Serial.println();
  Serial.print("WiFi OK IP=");
  Serial.println(WiFi.localIP());
}

String makeClientId() {
  uint64_t mac = ESP.getEfuseMac();
  char buf[32];
  snprintf(buf, sizeof(buf), "OTTOGO_%04X%08X", (uint16_t)(mac >> 32), (uint32_t)mac);
  return String(buf);
}

void connectMQTT() {
  mqtt.setServer(MQTT_HOST, MQTT_PORT);
  mqtt.setCallback(mqttCallback);

  while (!mqtt.connected()) {
    Serial.print("MQTT connecting... ");
    String cid = makeClientId();
    bool ok = mqtt.connect(cid.c_str());
    Serial.println(ok ? "OK" : "FAIL");
    if (!ok) delay(800);
  }
  mqtt.subscribe(MQTT_TOPIC_CMD);
  mqttPublishAck("READY");
}

// ===================== STATUS + Ultrasonic auto behavior =====================
unsigned long lastStatusMs = 0;
unsigned long lastUltraMs  = 0;
long lastDistance = -1;

void mqttPublishStatus() {
  String st = "{";
  st += "\"ip\":\"" + WiFi.localIP().toString() + "\",";
  st += "\"expr\":\"" + currentExpr + "\",";
  st += "\"speed\":\"" + speedName() + "\",";
  st += "\"ultra\":" + String(ultraEnabled ? 1 : 0) + ",";
  st += "\"dist\":" + String(lastDistance) + ",";
  st += "\"last\":\"" + lastCmd + "\"";
  st += "}";
  mqtt.publish(MQTT_TOPIC_STATUS, st.c_str());
}

unsigned long lastAutoGreetMs = 0;
const unsigned long AUTO_COOLDOWN_MS = 4500;

void ultrasonicAutoLoop() {
  if (!ultraEnabled) return;
  if (actionRunning) return;

  unsigned long now = millis();
  if (now - lastUltraMs < 250) return;
  lastUltraMs = now;

  long d = readDistanceMedian();
  if (d < 0 || d > 300) return;
  lastDistance = d;

  if (d <= 20 && (now - lastAutoGreetMs) > AUTO_COOLDOWN_MS) {
    lastAutoGreetMs = now;
    mqttPublishAck("AUTO greet");
    runAction("happy");
    mqttPublishAck("AUTO greet done");
  }
}

// ===================== Setup/Loop =====================
void setup() {
  Serial.begin(115200);
  delay(200);
  Serial.println("[BOOT] start");

  pinMode(US_TRIG, OUTPUT);
  pinMode(US_ECHO, INPUT);

  Serial.println("[TFT] init...");
  tftInitStable();
  tftHelloTestOnce();
  delay(200);
  exprNeutral();
  Serial.println("[TFT] ok");

  s1.attach(SERVO1, 600, 2400);
  s2.attach(SERVO2, 600, 2400);
  s3.attach(SERVO3, 600, 2400);
  s4.attach(SERVO4, 600, 2400);
  servoWriteAllSafe(90);

  i2sMutex = xSemaphoreCreateMutex();
  lockI2S();
  spk_ok = i2sInitSpeaker();
  if (spk_ok) playBeep1kHz_200ms_locked();
  unlockI2S();

  connectWiFi();
  connectMQTT();

  Serial.println("----- MQTT Topics -----");
  Serial.print("CMD    : "); Serial.println(MQTT_TOPIC_CMD);
  Serial.print("ACK    : "); Serial.println(MQTT_TOPIC_ACK);
  Serial.print("STATUS : "); Serial.println(MQTT_TOPIC_STATUS);
  Serial.println("-----------------------");

  mqttPublishAck("BOOT_OK");
}

void loop() {
  if (!mqtt.connected()) connectMQTT();
  mqtt.loop();

  ultrasonicAutoLoop();

  unsigned long now = millis();
  if (now - lastStatusMs > 2000) {
    lastStatusMs = now;
    mqttPublishStatus();
  }
}

/* ===== MQTT 指令總表(幼兒教具版)=====
[幼兒積木]
action=happy | angry | sleepy | neutral
expr=happy | angry | sleepy | neutral | mouth_open | mouth_close
spk=beep | roar
servo_speed=slow | normal | fast
ultra=on | off

[老師模式]
script=servo_speed=fast;action=happy;delay=300;spk=beep;expr=sleepy;servo_all=90,400;ultra=off
支援 token:action / expr / spk / servo_speed / servo_all / delay / ultra
====================================== */