2026年1月28日 星期三

[靈動狗] 網頁控制



   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
 829
 830
 831
 832
 833
 834
 835
 836
 837
 838
 839
 840
 841
 842
 843
 844
 845
 846
 847
 848
 849
 850
 851
 852
 853
 854
 855
 856
 857
 858
 859
 860
 861
 862
 863
 864
 865
 866
 867
 868
 869
 870
 871
 872
 873
 874
 875
 876
 877
 878
 879
 880
 881
 882
 883
 884
 885
 886
 887
 888
 889
 890
 891
 892
 893
 894
 895
 896
 897
 898
 899
 900
 901
 902
 903
 904
 905
 906
 907
 908
 909
 910
 911
 912
 913
 914
 915
 916
 917
 918
 919
 920
 921
 922
 923
 924
 925
 926
 927
 928
 929
 930
 931
 932
 933
 934
 935
 936
 937
 938
 939
 940
 941
 942
 943
 944
 945
 946
 947
 948
 949
 950
 951
 952
 953
 954
 955
 956
 957
 958
 959
 960
 961
 962
 963
 964
 965
 966
 967
 968
 969
 970
 971
 972
 973
 974
 975
 976
 977
 978
 979
 980
 981
 982
 983
 984
 985
 986
 987
 988
 989
 990
 991
 992
 993
 994
 995
 996
 997
 998
 999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
#include <Arduino.h>
#include <WiFi.h>
#include <WebServer.h>
#include <ESP32Servo.h>
#include <Adafruit_NeoPixel.h>
#include <Preferences.h>

// 資料型別定義
typedef  signed  char  wex_s8_t ;          // 8 位元有符號整數類型
typedef  signed  short  wex_s16_t ;        // 16 位元有符號整數類型
typedef  signed  long  wex_s32_t ;         // 32 位元有符號整數類型
typedef  signed  long  long  wex_s64_t ;    // 64 位元有符號整數類型
typedef  unsigned  char  wex_u8_t ;        // 8 位元無符號整數類型
typedef  unsigned  short  wex_u16_t ;      // 16 位元無符號整數類型
typedef  unsigned  long  wex_u32_t ;       // 32 位元無符號整數類型
typedef  unsigned  long  long  wex_u64_t ;  // 64 位元無符號整數類型
typedef  float  wex_f32_t ;               // 32 位元單精度浮點數類型
typedef  double  wex_f64_t ;              // 64 位元雙精確度浮點數類型

/* ========== 你的原本引腳定義保留 ========== */
#define WEX_LED_PIN 8
#define EYES_CTRL_PIN 6
#define LEFTHAND_CTRL_PIN 0
#define RIGHTHAND_CTRL_PIN 1
#define LEFTLEG_CTRL_PIN 10
#define RIGHTLEG_CTRL_PIN 7
#define TOUCH_SW_PIN 4
#define EYES_NUM 2
#define THERSHOLD_ANGLE 65

/* ========== 枚舉保留 ========== */
enum lightModel_t { LIGHT_MODEL_NORMAL=0, LIGHT_MODEL_BREATHING, LIGHT_MODEL_COLORFUL };
enum actionModel_t {
  ACTION_MODEL_NONE=0, ACTION_MODEL_FORWARD, ACTION_MODEL_LEFT, ACTION_MODEL_RIGHT, ACTION_MODEL_BACKWARD,
  ACTION_MODEL_STANDUP, ACTION_MODEL_GETDOWN, ACTION_MODEL_SITDOWN, ACTION_MODEL_STRETCH,
  ACTION_MODEL_HANDSHAKE, ACTION_MODEL_CRAWL, ACTION_MODEL_LEFTRIGHT, ACTION_MODEL_FRONTBACK,
  ACTION_MODEL_HEADFWD, ACTION_MODEL_HEADBACK
};
enum stateModel_t { STATE_MODEL_IDLE=0, STATE_MODEL_MOVING, STATE_MODEL_STANDUP, STATE_MODEL_GETDOWN, STATE_MODEL_SITDOWN };

/* ========== 舵機/狀態變數保留 ========== */
Servo leftHandServo, rightHandServo, leftLegServo, rightLegServo;
int leftHandAngle=90, rightHandAngle=90, leftLegAngle=90, rightLegAngle=90;
uint8_t actionModel=ACTION_MODEL_NONE;
uint8_t stateModel=STATE_MODEL_IDLE;
uint8_t moveSpeed=6;
uint8_t stepFlag=0;

/* ========== LED 相關保留 ========== */
Adafruit_NeoPixel strip(EYES_NUM, EYES_CTRL_PIN, NEO_GRB + NEO_KHZ800);
uint8_t lightLevel=0;                 // 0~255
uint8_t lightModel=LIGHT_MODEL_NORMAL;// 0/1/2
uint8_t ledRGB[3] = {255,255,255};

/* ========== 校準保留 ========== */
Preferences preferences;
int8_t leftHandOffset=0, rightHandOffset=0, leftLegOffset=0, rightLegOffset=0;

/* ========== 電池(你原本 ISR/Timer 若要保留可接回來) ========== */
const char* pcBatteryStatusStr[6]={"未知狀態","電池放電中","低電預警","電量耗盡","電池充電中","電池已充滿"};
uint8_t batteryStatus = 0;
uint32_t firmwareVersion = 0x010101;
uint32_t hardwareVersion = 0x0000;

/* ========== Web 控制 ========== */
WebServer server(80);
bool webCtrlFlag = false; // 取代你原本 wexcubeCtrlFlag:網頁正在控制時,先忽略觸碰按鍵

/* ========== 你原本宣告的函式(保留) ========== */
void updateLED(uint8_t r,uint8_t g,uint8_t b,uint8_t level);
void updateServo(uint8_t lh,uint8_t rh,uint8_t ll,uint8_t rl);
void standUp();
void getDown();
void sitDown();
void stretch();
void headForward();
void headBackward();
void saveOffsetsToFlash();

/* ========== 內建 HTML (手機/電腦瀏覽器都可) ========== */
static const char INDEX_HTML[] PROGMEM = R"HTML(
<!doctype html><html lang="zh-Hant"><head>
<meta charset="utf-8"/>
<meta name="viewport" content="width=device-width,initial-scale=1"/>
<title>RobotDog 控制台</title>
<style>
body{font-family:system-ui,-apple-system,"Segoe UI",Arial; margin:16px; background:#f6f7fb;}
.card{background:#fff;border-radius:14px;padding:14px;margin:10px 0;box-shadow:0 2px 10px rgba(0,0,0,.06);}
.row{display:flex;gap:10px;flex-wrap:wrap}
button{border:0;border-radius:12px;padding:14px 16px;font-size:16px;background:#2f6fed;color:#fff;min-width:120px}
button.secondary{background:#555}
button.danger{background:#d94a38}
label{display:block;margin:10px 0 6px}
input[type=range]{width:100%}
.small{color:#666;font-size:13px}
.grid{display:grid;grid-template-columns:repeat(3,minmax(0,1fr));gap:10px}
</style></head><body>

<h2>RobotDog 網頁控制</h2>

<div class="card">
  <div class="small" id="status">讀取狀態中…</div>
</div>

<div class="card">
  <h3>移動</h3>
  <div class="grid">
    <button id="btnF">前進</button>
    <button class="secondary" id="btnS">停止</button>
    <button id="btnB">後退</button>
    <button id="btnL">左轉</button>
    <button id="btnStand">站立</button>
    <button id="btnR">右轉</button>
  </div>
</div>

<div class="card">
  <h3>動作</h3>
  <div class="row">
    <button id="btnDown" class="secondary">趴下</button>
    <button id="btnSit" class="secondary">坐下</button>
    <button id="btnStretch" class="secondary">伸懶腰</button>
    <button id="btnShake" class="secondary">握手(按住)</button>
    <button id="btnCrawl" class="secondary">匍匐(按住)</button>
    <button id="btnLR" class="secondary">左右搖(按住)</button>
    <button id="btnFB" class="secondary">前後搖(按住)</button>
    <button id="btnHF" class="secondary">前頂</button>
    <button id="btnHB" class="secondary">後頂</button>
  </div>
</div>

<div class="card">
  <h3>動作速度</h3>
  <label>速度(1~10): <span id="spdV">6</span></label>
  <input id="spd" type="range" min="1" max="10" value="6"/>
</div>

<div class="card">
  <h3>舵機角度</h3>
  <label>左手 <span id="lhV">90</span></label><input id="lh" type="range" min="0" max="180" value="90">
  <label>右手 <span id="rhV">90</span></label><input id="rh" type="range" min="0" max="180" value="90">
  <label>左腳 <span id="llV">90</span></label><input id="ll" type="range" min="0" max="180" value="90">
  <label>右腳 <span id="rlV">90</span></label><input id="rl" type="range" min="0" max="180" value="90">
  <div class="small">拖曳會即時送出(建議站立狀態校準/調整)。</div>
</div>

<div class="card">
  <h3>眼睛燈效</h3>
  <label>亮度(0~100): <span id="lvV">0</span></label>
  <input id="lv" type="range" min="0" max="100" value="0"/>
  <div class="row">
    <button class="secondary" id="m0">正常</button>
    <button class="secondary" id="m1">呼吸</button>
    <button class="secondary" id="m2">彩燈</button>
  </div>
  <label>顏色</label>
  <input id="col" type="color" value="#ffffff"/>
</div>

<div class="card">
  <h3>校準</h3>
  <div class="row">
    <button class="danger" id="calReset">校準重設</button>
    <button id="calSet">校準寫入</button>
  </div>
  <div class="small">校準寫入:需站立且四肢接近 90° 才允許。</div>
</div>

<script>
const qs = o => Object.entries(o).map(([k,v])=>`${k}=${encodeURIComponent(v)}`).join("&");
async function api(path, params){ await fetch(path + "?" + qs(params)); }
function hold(btn, name){
  const down = () => api("/api/cmd",{name, v:1});
  const up   = () => api("/api/cmd",{name, v:0});
  btn.addEventListener("pointerdown", e=>{e.preventDefault(); down();});
  btn.addEventListener("pointerup",   e=>{e.preventDefault(); up();});
  btn.addEventListener("pointercancel",up);
  btn.addEventListener("pointerleave",up);
}
function click(btn, name){ btn.addEventListener("click", ()=>api("/api/cmd",{name, v:1})); }

hold(document.getElementById("btnF"),"forward");
hold(document.getElementById("btnB"),"backward");
hold(document.getElementById("btnL"),"left");
hold(document.getElementById("btnR"),"right");
click(document.getElementById("btnS"),"stop");
click(document.getElementById("btnStand"),"standup");
click(document.getElementById("btnDown"),"getdown");
click(document.getElementById("btnSit"),"sitdown");
click(document.getElementById("btnStretch"),"stretch");
hold(document.getElementById("btnShake"),"handshake");
hold(document.getElementById("btnCrawl"),"crawl");
hold(document.getElementById("btnLR"),"leftright");
hold(document.getElementById("btnFB"),"frontback");
click(document.getElementById("btnHF"),"headfwd");
click(document.getElementById("btnHB"),"headback");

const spd=document.getElementById("spd"), spdV=document.getElementById("spdV");
spd.oninput=()=>{spdV.textContent=spd.value; api("/api/cmd",{name:"speed", v:spd.value});};

const ids=["lh","rh","ll","rl"];
function sendServo(){
  api("/api/servo",{
    lh:document.getElementById("lh").value,
    rh:document.getElementById("rh").value,
    ll:document.getElementById("ll").value,
    rl:document.getElementById("rl").value
  });
}
for(const id of ids){
  const el=document.getElementById(id);
  const out=document.getElementById(id+"V");
  el.oninput=()=>{out.textContent=el.value; sendServo();};
}

const lv=document.getElementById("lv"), lvV=document.getElementById("lvV");
lv.oninput=()=>{lvV.textContent=lv.value; api("/api/eyes",{level:lv.value});};

document.getElementById("m0").onclick=()=>api("/api/eyes",{mode:0});
document.getElementById("m1").onclick=()=>api("/api/eyes",{mode:1});
document.getElementById("m2").onclick=()=>api("/api/eyes",{mode:2});

const col=document.getElementById("col");
col.oninput=()=>{
  const c=col.value;
  const r=parseInt(c.slice(1,3),16), g=parseInt(c.slice(3,5),16), b=parseInt(c.slice(5,7),16);
  api("/api/eyes",{r,g,b});
};

document.getElementById("calReset").onclick=()=>api("/api/calib",{name:"reset",v:1});
document.getElementById("calSet").onclick=()=>api("/api/calib",{name:"set",v:1});

async function poll(){
  try{
    const r=await fetch("/api/status");
    const j=await r.json();
    document.getElementById("status").textContent =
      `FW ${j.fw} / HW ${j.hw}|電池:${j.battery}|狀態:${j.state}|動作:${j.action}`;
  }catch(e){}
  setTimeout(poll,800);
}
poll();
</script>
</body></html>
)HTML";

/* ========== Web API handlers ========== */
String verToStr(uint32_t v){
  char s[16]; sprintf(s,"V%d.%d.%d",(v>>16)&0xFF,(v>>8)&0xFF,v&0xFF);
  return String(s);
}
String hwToStr(uint32_t v){
  char s[16]; sprintf(s,"V%d.%d",(v>>8)&0xFF,v&0xFF);
  return String(s);
}

void handleRoot(){
  server.send(200, "text/html; charset=utf-8", INDEX_HTML);
}

void handleCmd(){
  String name = server.arg("name");
  int v = server.arg("v").toInt();

  // 任何 API 呼叫都視為網頁正在控制(避免同時觸控鍵干擾)
  webCtrlFlag = true;

  if(name=="stop"){
    actionModel = ACTION_MODEL_NONE;
    webCtrlFlag = false;
    stepFlag = 0;
  }else if(name=="speed"){
    // 網頁用 1~10,你原本 moveSpeed 邏輯是 2~?,這裡直接用 1~10 映射到 2~20(你也可改)
    moveSpeed = constrain(v,1,10) * 2;
  }else if(name=="forward"){
    if(v){ standUp(); actionModel=ACTION_MODEL_FORWARD; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="backward"){
    if(v){ standUp(); actionModel=ACTION_MODEL_BACKWARD; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="left"){
    if(v){ standUp(); actionModel=ACTION_MODEL_LEFT; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="right"){
    if(v){ standUp(); actionModel=ACTION_MODEL_RIGHT; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="standup"){
    actionModel = ACTION_MODEL_STANDUP;
  }else if(name=="getdown"){
    actionModel = ACTION_MODEL_GETDOWN;
  }else if(name=="sitdown"){
    actionModel = ACTION_MODEL_SITDOWN;
  }else if(name=="stretch"){
    actionModel = ACTION_MODEL_STRETCH;
  }else if(name=="handshake"){
    if(v){ sitDown(); actionModel=ACTION_MODEL_HANDSHAKE; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="crawl"){
    if(v){ sitDown(); actionModel=ACTION_MODEL_CRAWL; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="leftright"){
    if(v){ standUp(); actionModel=ACTION_MODEL_LEFTRIGHT; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="frontback"){
    if(v){ standUp(); actionModel=ACTION_MODEL_FRONTBACK; }
    else { actionModel=ACTION_MODEL_NONE; webCtrlFlag=false; }
  }else if(name=="headfwd"){
    actionModel = ACTION_MODEL_HEADFWD;
  }else if(name=="headback"){
    actionModel = ACTION_MODEL_HEADBACK;
  }

  server.send(200,"text/plain","OK");
}

void handleServo(){
  leftHandAngle  = constrain(server.arg("lh").toInt(),0,180);
  rightHandAngle = constrain(server.arg("rh").toInt(),0,180);
  leftLegAngle   = constrain(server.arg("ll").toInt(),0,180);
  rightLegAngle  = constrain(server.arg("rl").toInt(),0,180);
  updateServo(leftHandAngle,rightHandAngle,leftLegAngle,rightLegAngle);
  server.send(200,"text/plain","OK");
}

void handleEyes(){
  if(server.hasArg("level")){
    int lv = constrain(server.arg("level").toInt(),0,100);
    lightLevel = map(lv,0,100,0,255);
  }
  if(server.hasArg("mode")){
    lightModel = constrain(server.arg("mode").toInt(),0,2);
  }
  if(server.hasArg("r") && server.hasArg("g") && server.hasArg("b")){
    ledRGB[0]=constrain(server.arg("r").toInt(),0,255);
    ledRGB[1]=constrain(server.arg("g").toInt(),0,255);
    ledRGB[2]=constrain(server.arg("b").toInt(),0,255);
  }
  if(lightLevel==0) updateLED(0,0,0,0);
  else updateLED(ledRGB[0],ledRGB[1],ledRGB[2],lightLevel);
  server.send(200,"text/plain","OK");
}

void handleCalib(){
  String name = server.arg("name");
  if(name=="reset"){
    leftHandOffset=rightHandOffset=leftLegOffset=rightLegOffset=0;
    saveOffsetsToFlash();
    server.send(200,"text/plain","RESET_OK");
    return;
  }
  if(name=="set"){
    // 你的原本規則:必須站立狀態且角度接近 90
    if(stateModel != STATE_MODEL_STANDUP){
      server.send(400,"text/plain","ERR_NOT_STANDUP");
      return;
    }
    if(abs(leftHandAngle-90)>15 || abs(rightHandAngle-90)>15 || abs(leftLegAngle-90)>15 || abs(rightLegAngle-90)>15){
      server.send(400,"text/plain","ERR_TOO_MUCH_OFFSET");
      return;
    }
    leftHandOffset  += (leftHandAngle-90);
    rightHandOffset += (rightHandAngle-90);
    leftLegOffset   += (leftLegAngle-90);
    rightLegOffset  += (rightLegAngle-90);
    saveOffsetsToFlash();
    leftHandAngle=rightHandAngle=leftLegAngle=rightLegAngle=90;
    updateServo(leftHandAngle,rightHandAngle,leftLegAngle,rightLegAngle);
    server.send(200,"text/plain","SET_OK");
    return;
  }
  server.send(400,"text/plain","ERR_BAD_REQ");
}

void handleStatus(){
  String json = "{";
  json += "\"fw\":\""+verToStr(firmwareVersion)+"\",";
  json += "\"hw\":\""+hwToStr(hardwareVersion)+"\",";
  json += "\"battery\":\""+String(pcBatteryStatusStr[batteryStatus])+"\",";
  json += "\"state\":"+String(stateModel)+",";
  json += "\"action\":"+String(actionModel);
  json += "}";
  server.send(200,"application/json",json);
}

/* ========== setup / loop ========== */
void setup(){
  setCpuFrequencyMhz(80);
  delay(500);
  Serial.begin(115200);

  pinMode(WEX_LED_PIN, OUTPUT);
  digitalWrite(WEX_LED_PIN, LOW); // 有開機就亮(你可自行調)

  // 舵機 50Hz
  leftHandServo.setPeriodHertz(50);
  rightHandServo.setPeriodHertz(50);
  leftLegServo.setPeriodHertz(50);
  rightLegServo.setPeriodHertz(50);
  leftHandServo.attach(LEFTHAND_CTRL_PIN, 500, 2500);
  rightHandServo.attach(RIGHTHAND_CTRL_PIN, 500, 2500);
  leftLegServo.attach(LEFTLEG_CTRL_PIN, 500, 2500);
  rightLegServo.attach(RIGHTLEG_CTRL_PIN, 500, 2500);

  // 讀取校準
  preferences.begin("servo", false);
  leftHandOffset  = preferences.getInt("leftHandOffset",0);
  rightHandOffset = preferences.getInt("rightHandOffset",0);
  leftLegOffset   = preferences.getInt("leftLegOffset",0);
  rightLegOffset  = preferences.getInt("rightLegOffset",0);
  preferences.end();

  updateServo(leftHandAngle,rightHandAngle,leftLegAngle,rightLegAngle);

  strip.begin();
  strip.setBrightness(lightLevel);
  strip.show();

  pinMode(TOUCH_SW_PIN, INPUT_PULLDOWN);

  // 硬體版本讀取(保留你原本判斷)
  pinMode(20, INPUT_PULLUP);
  pinMode(21, INPUT_PULLUP);
  delay(100);
  uint8_t pin20Value1 = digitalRead(20);
  uint8_t pin21Value1 = digitalRead(21);
  pinMode(20, INPUT_PULLDOWN);
  pinMode(21, INPUT_PULLDOWN);
  delay(100);
  uint8_t pin20Value2 = digitalRead(20);
  uint8_t pin21Value2 = digitalRead(21);
  if(pin20Value1==HIGH && pin21Value1==HIGH && pin20Value2==LOW && pin21Value2==LOW) hardwareVersion=0x0100;
  else hardwareVersion=0x0101;

  // === WiFi AP ===
  uint64_t chipid = ESP.getEfuseMac();
  char ssid[32];
  sprintf(ssid, "RobotDog02-%02X%02X%02X", (uint8_t)(chipid>>16), (uint8_t)(chipid>>8), (uint8_t)chipid);
  WiFi.mode(WIFI_AP);
  WiFi.softAP(ssid, "12345678"); // 你可改密碼
  IPAddress ip = WiFi.softAPIP();
  Serial.printf("AP SSID: %s\n", ssid);
  Serial.printf("Open: http://%s/\n", ip.toString().c_str());

  // Web routes
  server.on("/", handleRoot);
  server.on("/api/cmd", handleCmd);
  server.on("/api/servo", handleServo);
  server.on("/api/eyes", handleEyes);
  server.on("/api/calib", handleCalib);
  server.on("/api/status", handleStatus);
  server.begin();
}

void loop(){
  server.handleClient();

  // 避免阻塞
  delay(20);

  // === 觸碰按鍵控制保留,但網頁控制中先不進來 ===webCtrlFlag
  if  ( webCtrlFlag  ==  false )
  {
    // 觸摸事件處理:
    // 1. 單擊,眼睛燈光開關
    // 2. 雙擊,站立/趴下
    int  SW  =  digitalRead ( TOUCH_SW_PIN );  // 讀取觸控按鍵值

    if  ( SW  ==  HIGH )  // 觸碰按鍵按下
    {
      wex_u32_t  i  =  0 ;
      delay ( 30 );  // 防抖動延遲

      // 等待搖桿按鍵放開
      while  ( digitalRead ( TOUCH_SW_PIN )  ==  HIGH )
      {
        i ++ ;
        delay ( 10 ); 
      }
      if  ( i  <  50 )
      {
        while  ( i  <  50 )
        {
          delay ( 10 );
          if  ( digitalRead ( TOUCH_SW_PIN )  ==  HIGH )  // 觸摸按鍵再次按下
            break ;
          i ++ ;
        }
      }
      if  ( i  <  50 )
      {
        if  ( leftLegAngle  >=  70 )
          actionModel  =  ACTION_MODEL_GETDOWN ;
        else
          actionModel  =  ACTION_MODEL_STANDUP ;
        delay ( 500 );  // 等手拿開
      }
      else
      {
        lightLevel  =  lightLevel  ==  0  ?  128  :  0 ;  // 切換眼睛燈光開關
        if  ( lightLevel  ==  0 )
        {
          updateLED ( 0 ,  0 ,  0 ,  0 );  // 關閉燈光
//          wex_setValue ( SLIDER_EYES_LEVEL_ID ,  0 );  // 更新小程式滑桿值
        }
        else
        {
          updateLED ( ledRGB [ 0 ],  ledRGB [ 1 ],  ledRGB [ 2 ],  lightLevel );  // 開啟燈光
//          wex_setValue ( SLIDER_EYES_LEVEL_ID ,  map ( lightLevel ,  0 ,  255 ,  0 ,  100 ));  // 更新小程式滑桿值
        }
      }
    } 
  }

  // === 眼睛燈光控制(保留你的原本邏輯)===
  if(lightLevel){
    if(lightModel==LIGHT_MODEL_NORMAL){
      static uint32_t cnt=0; cnt++;
      if(cnt>=10){ cnt=0; updateLED(ledRGB[0],ledRGB[1],ledRGB[2],lightLevel); }
    }else if(lightModel==LIGHT_MODEL_BREATHING){
      static uint8_t level=0, dir=0; static float s=0.0f;
      float v = (float)lightLevel/50.0f;
      if(dir){
        if(level>=lightLevel){ dir=0; s=(float)lightLevel; }
        else { s+=v; level = s<(float)lightLevel ? (uint8_t)s : lightLevel; }
      }else{
        if(level==0){ dir=1; s=0.0f; }
        else { s-=v; level = s>0.0f ? (uint8_t)s : 0; }
      }
      updateLED(ledRGB[0],ledRGB[1],ledRGB[2],level);
    }else if(lightModel==LIGHT_MODEL_COLORFUL){
      static long firstPixelHue=0;
      firstPixelHue += 256;
      if(firstPixelHue>=65536) firstPixelHue=0;
      for(int i=0;i<strip.numPixels();i++){
        int pixelHue = firstPixelHue + (i * 65536L / strip.numPixels());
        strip.setPixelColor(i, strip.gamma32(strip.ColorHSV(pixelHue)));
      }
      strip.show();
    }
  }

  // === 動作狀態機(保留你原本 switch(actionModel) 整段)===
  switch(actionModel){
    case  ACTION_MODEL_FORWARD :  // 前進
    {
      if  ( stepFlag  ==  0 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  <=  THERSHOLD_ANGLE )  stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        rightHandAngle  +=  moveSpeed ;
        leftLegAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  >=  ( 180  -  THERSHOLD_ANGLE ))  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  90 )  stepFlag  =  3 ;
      }
      else  if  ( stepFlag  ==  3 )
      {
        rightHandAngle  -=  moveSpeed ;
        leftLegAngle  -=  moveSpeed ;
        
        if  ( rightHandAngle  <=  THERSHOLD_ANGLE )  stepFlag  =  4 ;
      }
      else  if  ( stepFlag  ==  4 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  ( 180  -  THERSHOLD_ANGLE ))  stepFlag  =  5 ;
      }
      else  if  ( stepFlag  ==  5 )
      {
        rightHandAngle  +=  moveSpeed ;
        leftLegAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  >=  90 )  stepFlag  =  6 ;
      }
      else  if  ( stepFlag  ==  6 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  <=  90 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case  ACTION_MODEL_LEFT :  // 左轉
    {
      if  ( stepFlag  ==  0 )
      {
        rightHandAngle  -=  moveSpeed ;
        leftLegAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  <=  THERSHOLD_ANGLE )  stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        rightLegAngle  +=  moveSpeed ;
        leftHandAngle  -=  moveSpeed ;
        
        if  ( rightLegAngle  >=  ( 180  -  THERSHOLD_ANGLE ))  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        rightHandAngle  +=  moveSpeed ;
        leftLegAngle  -=  moveSpeed ;
        
        if  ( rightHandAngle  >=  90 )  stepFlag  =  3 ;
      }
      else  if  ( stepFlag  ==  3 )
      {
        rightLegAngle  -=  moveSpeed ;
        leftHandAngle  +=  moveSpeed ;
        
        if  ( rightLegAngle  <=  90 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case  ACTION_MODEL_RIGHT :  // 右轉
    {
      if  ( stepFlag  ==  0 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  <=  THERSHOLD_ANGLE )  stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        leftLegAngle  +=  moveSpeed ;
        rightHandAngle  -=  moveSpeed ;
        
        if  ( leftLegAngle  >=  ( 180  -  THERSHOLD_ANGLE ))  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  >=  90 )  stepFlag  =  3 ;
      }
      else  if  ( stepFlag  ==  3 )
      {
        leftLegAngle  -=  moveSpeed ;
        rightHandAngle  +=  moveSpeed ;
        
        if  ( leftLegAngle  <=  90 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case  ACTION_MODEL_BACKWARD :  // 後退
    {
      if  ( stepFlag  ==  0 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  ( 180  -  THERSHOLD_ANGLE ))  stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        rightHandAngle  -=  moveSpeed ;
        leftLegAngle  -=  moveSpeed ;
        
        if  ( rightHandAngle  <=  THERSHOLD_ANGLE )  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  <=  90 )  stepFlag  =  3 ;
      }
      else  if  ( stepFlag  ==  3 )
      {
        rightHandAngle  +=  moveSpeed ;
        leftLegAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  >=  ( 180  -  THERSHOLD_ANGLE ))  stepFlag  =  4 ;
      }
      else  if  ( stepFlag  ==  4 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  <=  THERSHOLD_ANGLE )  stepFlag  =  5 ;
      }
      else  if  ( stepFlag  ==  5 )
      {
        rightHandAngle  -=  moveSpeed ;
        leftLegAngle  -=  moveSpeed ;
        
        if  ( rightHandAngle  <=  90 )  stepFlag  =  6 ;
      }
      else  if  ( stepFlag  ==  6 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  90 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;
    case ACTION_MODEL_STANDUP:
      standUp(); actionModel=ACTION_MODEL_NONE; stateModel=STATE_MODEL_STANDUP; break;
    case ACTION_MODEL_GETDOWN:
      getDown(); actionModel=ACTION_MODEL_NONE; stateModel=STATE_MODEL_GETDOWN; break;
    case ACTION_MODEL_SITDOWN:
      sitDown(); actionModel=ACTION_MODEL_NONE; stateModel=STATE_MODEL_SITDOWN; break;
    case ACTION_MODEL_STRETCH:
      stretch(); actionModel=ACTION_MODEL_NONE; stateModel=STATE_MODEL_STANDUP; break;
      case  ACTION_MODEL_HANDSHAKE :  // 握手
    {
      if  ( stepFlag  ==  0 )
      {
        rightHandAngle  -=  moveSpeed ;
        
        if  ( rightHandAngle  <=  15 )  stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        rightHandAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  >=  50 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case  ACTION_MODEL_CRAWL :  // 匍匐前進
    {
      if  ( stepFlag  ==  0 )
      {
        leftHandAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  <=  60 )  stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        rightHandAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  >=  140 )  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        leftHandAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  100 )  stepFlag  =  3 ;
      }
      else  if  ( stepFlag  ==  3 )
      {
        rightHandAngle  -=  moveSpeed ;
        
        if  ( rightHandAngle  <=  60 )  stepFlag  =  4 ;
      }
      else  if  ( stepFlag  ==  4 )
      {
        leftHandAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  140 )  stepFlag  =  5 ;
      }
      else  if  ( stepFlag  ==  5 )
      {
        rightHandAngle  +=  moveSpeed ;
        
        if  ( rightHandAngle  >=  100 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case  ACTION_MODEL_LEFTRIGHT :  // 左右搖晃
    {
      if  ( stepFlag  ==  0 )
      {
        while  (( abs ( rightHandAngle  -  20 )  >  moveSpeed )  ||  ( abs ( rightLegAngle  -  20 )  >  moveSpeed ))
        {
          if  ( rightHandAngle  <  20 )  rightHandAngle  +=  moveSpeed ;
          else  if  ( rightHandAngle  >  20 )  rightHandAngle  -=  moveSpeed ;

          if  ( rightLegAngle  <  20 )  rightLegAngle  +=  moveSpeed ;
          else  if  ( rightLegAngle  >  20 )  rightLegAngle  -=  moveSpeed ;

          delay ( 10 );  // 延時,避免過快

          updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
        }
  
        stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightHandAngle  +=  moveSpeed ;
        leftLegAngle  -=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  <=  20 )  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightHandAngle  -=  moveSpeed ;
        leftLegAngle  +=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  >=  90 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case  ACTION_MODEL_FRONTBACK :  // 前後搖晃
    {
      if  ( stepFlag  ==  0 )
      {
        while  (( abs ( leftLegAngle  -  160 )  >  moveSpeed )  ||  ( abs ( rightLegAngle  -  160 )  >  moveSpeed ))
        {
          if  ( leftLegAngle  >  160 )  leftLegAngle  -=  moveSpeed ;
          else  if  ( leftLegAngle  <  160 )  leftLegAngle  +=  moveSpeed ;

          if  ( rightLegAngle  >  160 )  rightLegAngle  -=  moveSpeed ;
          else  if  ( rightLegAngle  <  160 )  rightLegAngle  +=  moveSpeed ;

          delay ( 10 );  // 延時,避免過快

          updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
        }
  
        stepFlag  =  1 ;
      }
      else  if  ( stepFlag  ==  1 )
      {
        leftHandAngle  -=  moveSpeed ;
        rightHandAngle  -=  moveSpeed ;
        leftLegAngle  -=  moveSpeed ;
        rightLegAngle  -=  moveSpeed ;
        
        if  ( leftHandAngle  <=  20 )  stepFlag  =  2 ;
      }
      else  if  ( stepFlag  ==  2 )
      {
        leftHandAngle  +=  moveSpeed ;
        rightHandAngle  +=  moveSpeed ;
        leftLegAngle  +=  moveSpeed ;
        rightLegAngle  +=  moveSpeed ;
        
        if  ( leftHandAngle  >=  90 )  stepFlag  =  0 ;
      }
      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度

      stateModel  =  STATE_MODEL_MOVING ;  // 設定狀態為移動
    }
    break ;

    case ACTION_MODEL_HEADFWD:
      headForward(); actionModel=ACTION_MODEL_NONE; stateModel=STATE_MODEL_STANDUP; break;
    case ACTION_MODEL_HEADBACK:
      headBackward(); actionModel=ACTION_MODEL_NONE; stateModel=STATE_MODEL_STANDUP; break;

    default:
      stepFlag=0;
      break;
  }
}

/**
* @brief LED 顏色、亮度更新
* @param ucRed 紅色分量
* @param ucGreen 綠色分量
* @param ucBlue 藍色分量
* @param ucLevel 亮度
* @retval None
*/
void  updateLED ( wex_u8_t  ucRed ,  wex_u8_t  ucGreen ,  wex_u8_t  ucBlue ,  wex_u8_t  ucLevel )
{
  for  ( int  i  =  0 ;  i  <  EYES_NUM ;  i ++ )
  {
    strip . setPixelColor ( i ,  strip . Color ( ucRed ,  ucGreen ,  ucBlue ));
  }
  strip . setBrightness ( ucLevel );
  strip . show ();
}
// 將舵機偏移量儲存到Flash
void  saveOffsetsToFlash ()  {
  preferences . begin ( "servo" ,  false );
  preferences . putInt ( "leftHandOffset" ,  leftHandOffset );
  preferences . putInt ( "rightHandOffset" ,  rightHandOffset );
  preferences . putInt ( "leftLegOffset" ,  leftLegOffset );
  preferences . putInt ( "rightLegOffset" ,  rightLegOffset );
  preferences . end ();
}


/**
* @brief 舵機更新
* @param ucLeftHand 左手舵機角度
* @param ucRightHand 右手舵機角度
* @param ucLeftLeg 左腳舵機角度
* @param ucRightLeg 右腳舵機角度
* @retval None
*/
void  updateServo ( wex_u8_t  ucLeftHand ,  wex_u8_t  ucRightHand ,  wex_u8_t  ucLeftLeg ,  wex_u8_t  ucRightLeg )
{
  // 根據偏移量修正舵機角度
  int  leftHand  =  ucLeftHand  +  leftHandOffset ;
  int  rightHand   =  ucRightHand  +  rightHandOffset ;
  int  leftLeg   =  ucLeftLeg  +  leftLegOffset ;
  int  rightLeg   =  ucRightLeg  +  rightLegOffset ;

  leftHand  =  constrain ( leftHand ,  0 ,  180 );  // 限制角度範圍
  rightHand  =  constrain ( rightHand ,  0 ,  180 );  // 限制角度範圍
  leftLeg  =  constrain ( leftLeg ,  0 ,  180 );  // 限制角度範圍
  rightLeg  =  constrain ( rightLeg ,  0 ,  180 );  // 限制角度範圍

  // 把舵機角度統一化,0為最前,180為最後
  rightHand  =  180  -  rightHand ;  // 右舵機角度反轉
  rightLeg  =  180  -  rightLeg ;  // 右腳舵機角度反轉

  leftHandServo . write ( leftHand );   // 設定左手舵機角度
  rightHandServo . write ( rightHand );   // 設定右手舵機角度
  leftLegServo . write ( leftLeg );   // 設定左腳舵機角度
  rightLegServo . write ( rightLeg );   // 設定右腳舵機角度
}




// 站立
void  standUp ()
{
  while  (( abs ( leftLegAngle  -  90 )  >  5 )  ||  ( abs ( rightLegAngle  -  90 )  >  5 ))
  {
    if  ( leftLegAngle  >  90 )  leftLegAngle  -=  3 ;
    else  if  ( leftLegAngle  <  90 )  leftLegAngle  +=  3 ;

    if  ( rightLegAngle  >  90 )  rightLegAngle  -=  3 ;
    else  if  ( rightLegAngle  <  90 )  rightLegAngle  +=  3 ;

    delay ( 20 );  // 延時,避免過快

    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }
  leftLegAngle  =  90 ;
  rightLegAngle  =  90 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  


  while  (( abs ( leftHandAngle  -  90 )  >  5 )  ||  ( abs ( rightHandAngle  -  90 )  >  5 ))
  {
    if  ( leftHandAngle  >  90 )  leftHandAngle  -=  5 ;
    else  if  ( leftHandAngle  <  90 )  leftHandAngle  +=  5 ;

    if  ( rightHandAngle  >  90 )  rightHandAngle  -=  5 ;
    else  if  ( rightHandAngle  <  90 )  rightHandAngle  +=  5 ;

    delay ( 20 );  // 延時,避免過快
    
    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }
  leftHandAngle  =  90 ;
  rightHandAngle  =  90 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );


}

// 趴下
void  getDown ()
{
  while  (( abs ( leftLegAngle  -  15 )  >  5 )  ||  ( abs ( rightLegAngle  -  15 )  >  5 ))
  {
    if  ( leftLegAngle  >  15 )  leftLegAngle  -=  5 ;
    else  if  ( leftLegAngle  <  15 )  leftLegAngle  +=  5 ;

    if  ( rightLegAngle  >  15 )  rightLegAngle  -=  5 ;
    else  if  ( rightLegAngle  <  15 )  rightLegAngle  +=  5 ;

    delay ( 20 );  // 延時,避免過快

    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }
  leftLegAngle  =  15 ;
  rightLegAngle  =  15 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  
  while  (( abs ( leftHandAngle  -  15 )  >  5 )  ||  ( abs ( rightHandAngle  -  15 )  >  5 ))
  {
    if  ( leftHandAngle  >  15 )  leftHandAngle  -=  5 ;
    else  if  ( leftHandAngle  <  15 )  leftHandAngle  +=  5 ;

    if  ( rightHandAngle  >  15 )  rightHandAngle  -=  5 ;
    else  if  ( rightHandAngle  <  15 )  rightHandAngle  +=  5 ;

    delay ( 20 );  // 延時,避免過快
    
    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }
  leftHandAngle  =  15 ;
  rightHandAngle  =  15 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
}

// 坐下
void  sitDown ()
{
  while  (( abs ( leftLegAngle  -  40 )  >  5 )  ||  ( abs ( rightLegAngle  -  40 )  >  5 ))
  {
    if  ( leftLegAngle  >  40 )  leftLegAngle  -=  3 ;
    else  if  ( leftLegAngle  <  40 )  leftLegAngle  +=  3 ;

    if  ( rightLegAngle  >  40 )  rightLegAngle  -=  3 ;
    else  if  ( rightLegAngle  <  40 )  rightLegAngle  +=  3 ;

    delay ( 20 );  // 延時,避免過快

    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }
  leftLegAngle  =  40 ;
  rightLegAngle  =  40 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  
  while  (( abs ( leftHandAngle  -  100 )  >  5 )  ||  ( abs ( rightHandAngle  -  100 )  >  5 ))
  {
    if  ( leftHandAngle  >  100 )  leftHandAngle  -=  5 ;
    else  if  ( leftHandAngle  <  100 )  leftHandAngle  +=  5 ;

    if  ( rightHandAngle  >  100 )  rightHandAngle  -=  5 ;
    else  if  ( rightHandAngle  <  100 )  rightHandAngle  +=  5 ;

    delay ( 20 );  // 延時,避免過快
    
    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }
  leftHandAngle  =  100 ;
  rightHandAngle  =  100 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
}

// 伸懶腰
void  stretch ()
{
  standUp ();  // 先站立

  // 避免長時間未處理藍牙接收訊息,導致WeXCube 斷開連接
  //wex_process ();
  
  while  ( leftHandAngle  >=  15 )
  {
    leftHandAngle  -=  3 ;
    rightHandAngle  -=  3 ;
    leftLegAngle  -=  1 ;
    rightLegAngle  -=  1 ;

    delay ( 20 );  // 延時,避免過快

    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }

  // 避免長時間未處理藍牙接收訊息,導致WeXCube 斷開連接
  //wex_process ();

  int  n  =  2 ;
  while  ( n -- )
  {
    while  ( leftHandAngle  <=  25 )
    {
      leftHandAngle  +=  1 ;
      rightHandAngle  +=  1 ;

      delay ( 20 );  // 延時,避免過快

      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
    }

    while  ( leftHandAngle  >=  15 )
    {
      leftHandAngle  -=  2 ;
      rightHandAngle  -=  2 ;

      delay ( 20 );  // 延時,避免過快

      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
    }
  }

  // 避免長時間未處理藍牙接收訊息,導致WeXCube 斷開連接
  //wex_process ();
  
  while  ( leftLegAngle  <=  165 )
  {
    leftHandAngle  +=  3 ;
    rightHandAngle  +=  3 ;
    leftLegAngle  +=  3 ;
    rightLegAngle  +=  3 ;

    delay ( 20 );  // 延時,避免過快
    
    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }

  // 避免長時間未處理藍牙接收訊息,導致WeXCube 斷開連接
  //wex_process ();

  n  =  2 ;
  while  ( n -- )
  {
    while  ( leftLegAngle  >=  155 )
    {
      leftLegAngle  -=  1 ;
      rightLegAngle  -=  1 ;

      delay ( 20 );  // 延時,避免過快

      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
    }

    while  ( leftLegAngle  <=  165 )
    {
      leftLegAngle  +=  2 ;
      rightLegAngle  +=  2 ;

      delay ( 20 );  // 延時,避免過快

      updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
    }
  }

  // 避免長時間未處理藍牙接收訊息,導致WeXCube 斷開連接
  //wex_process ();

  while  ( leftHandAngle  >=  90 )
  {
    leftHandAngle  -=  1 ;
    rightHandAngle  -=  1 ;

    delay ( 20 );  // 延時,避免過快

    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }

  // 避免長時間未處理藍牙接收訊息,導致WeXCube 斷開連接
  //wex_process ();

  while  ( leftLegAngle  >=  90 )
  {
    leftLegAngle  -=  3 ;
    rightLegAngle  -=  3 ;

    delay ( 20 );  // 延時,避免過快

    updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );   // 更新舵機角度
  }

  actionModel  =  ACTION_MODEL_NONE ;  // 停止動作
}

// 前頂
void  headForward ()
{
  standUp ();
  leftHandAngle  =  140 ;
  rightHandAngle  =  140 ;
  leftLegAngle  =  150 ;
  rightLegAngle  =  150 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  delay ( 200 );
  leftHandAngle  =  90 ;
  rightHandAngle  =  90 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  delay ( 100 );
  leftLegAngle  =  90 ;
  rightLegAngle  =  90 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  delay ( 100 );
}

// 後頂
void  headBackward ()
{
  standUp ();
  leftHandAngle  =  30 ;
  rightHandAngle  =  30 ;
  leftLegAngle  =  40 ;
  rightLegAngle  =  40 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  delay ( 200 );
  leftLegAngle  =  90 ;
  rightLegAngle  =  90 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  delay ( 100 );
  leftHandAngle  =  90 ;
  rightHandAngle  =  90 ;
  updateServo ( leftHandAngle ,  rightHandAngle ,  leftLegAngle ,  rightLegAngle );
  delay ( 100 );
}

/* ======= 以下函式請用你原本的版本(直接複製貼上)=======
   updateLED, updateServo,
   selectEyesColor/selectEyesModel 已不需要(可刪)
   standUp/getDown/sitDown/stretch/headForward/headBackward,
   saveOffsetsToFlash
*/

沒有留言:

張貼留言