
予算3万円でつくる BLDC 2足歩行ロボット 第5号
ー2足歩行ロボットの動作を楽しむ1ー
前回は2足歩行ロボット HM-01 を完成させて PS4コントローラによる足動作を楽しみました。
ここでは動作シーケンスを組んで足踏みや歩行動作を楽しみます。
目次
ATOM用Arduinoコード
前回からATOM用のコードのみを変更して足踏み・歩行動作を実現します。
動作はPS4コントローラから指定します。
まずはコードを紹介します。
詳細は次節以降に記載します。
環境バージョンはこれまでと同様で以下の通りです。
Arduino IDEバージョン:ver. 1.8.19
ESP32ライブラリ:ver. 2.0.13
M5Atomライブラリ:ver. 0.1.3
Kalman Filter Library :ver. 1.0.2
PS4Controllerライブラリ:ver. 1.1.0
SimpleFOCライブラリ:ver. 2.3.3
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 |
enum class ModeT : uint8_t; #include <M5Atom.h> #include <Kalman.h> #include <WiFi.h> #include <WebServer.h> #include <Preferences.h> #include <PS4Controller.h> #include "driver/twai.h" #include <SimpleFOC.h> twai_message_t rx_msg; WebServer server(80); const char ssid[] = "ATOM"; // SSID const char pass[] = "password"; // password const IPAddress ip(192, 168,22, 90); // IPアドレス const IPAddress subnet(255, 255, 255, 0); // サブネットマスク int Motion = 0; int idleState = 0; int delay1 = 50, delay2 = 140; float xZero = 10.0, zZero = 99.0; float dx1 = 10.0, dx2 = 5.0; float dz1 = 3.0, dz2 = 16.0; float tim; unsigned long time_mSt; LowPassFilter filter = LowPassFilter(0.3); float tf = 0.3; float th = 30.0; int stateJudge = 0; float torqueL = 0.0, torqueR = 0.0; float preTorque = 0.0, currentTorque = 0.0, diffTorque = 0.0; float offsetX = 0.0, offsetY = 0.0; int lastLStickX = 0, lastLStickY = 0, lastRStickX = 0, lastRStickY = 0; unsigned long oldTime = 0, loopTime, nowTime, startTime; float dt; float accX = 0, accY = 0, accZ = 0; float gyroX = 0, gyroY = 0, gyroZ = 0; float theta_X = 0.0, theta_Y = 0.0; float theta_Xdot = 0.0, theta_Ydot = 0.0; Kalman kalmanX, kalmanY; float kalAngleX, kalAngleDotX, kalAngleY, kalAngleDotY; float Kp = 0.3, Kd = 0.2; float rollVal = 0.0, rollCtrlL = 0.0, rollCtrlR = 0.0; Preferences preferences; //加速度センサから傾きデータ取得 [deg] void get_theta() { M5.IMU.getAccelData(&accX,&accY,&accZ); //傾斜角導出 単位はdeg theta_X = atan2(accY, -accZ) * 57.29578f + offsetX; theta_Y = -atan2(-accX, -accZ) * 57.29578f + offsetY; } //角速度取得 void get_gyro_data() { M5.IMU.getGyroData(&gyroX,&gyroY,&gyroZ); theta_Xdot = -gyroX; theta_Ydot = gyroY; } //CAN送信 L void sendL(float xL, float hL) { twai_message_t msg = {}; msg.identifier = 0x121; msg.extd = 0; // 標準ID(11bit) msg.data_length_code = 8; // floatをバイト配列にコピー memcpy(&msg.data[0], &xL, 4); memcpy(&msg.data[4], &hL, 4); // 送信 twai_transmit(&msg, 0); } //CAN送信 R void sendR(float xR, float hR) { twai_message_t msg = {}; msg.identifier = 0x122; msg.extd = 0; // 標準ID(11bit) msg.data_length_code = 8; // floatをバイト配列にコピー memcpy(&msg.data[0], &xR, 4); memcpy(&msg.data[4], &hR, 4); // 送信 twai_transmit(&msg, 0); } //CAN送信 Roll void sendRoll(float angL, float angR) { twai_message_t msg = {}; msg.identifier = 0x123; msg.extd = 0; // 標準ID(11bit) msg.data_length_code = 8; // floatをバイト配列にコピー memcpy(&msg.data[0], &angL, 4); memcpy(&msg.data[4], &angR, 4); // 送信 twai_transmit(&msg, 0); } //モード定義 enum class ModeT : uint8_t {Idle, Step, Ad, Back}; //モードを設定して実行 void setMotion(ModeT m) { switch (m) { case ModeT::Step: //足踏み if(Motion == 0){ sendL(xZero, zZero); Motion = 1; time_mSt = millis(); tim = 0; }else if(Motion == 1){ tim = millis() - time_mSt; if(tim <= delay1){ sendR(xZero, zZero + dz1 / delay1 * tim); //0 -> dz1 }else{ time_mSt = millis(); tim = 0; Motion = 2; } }else if(Motion == 2 && tim <= delay2){ tim = millis() - time_mSt; sendR(xZero, zZero + dz1 - (dz1 + dz2) / delay2 * tim); //dz1 -> -dz2 }else if(Motion == 2 && tim > delay2){ Motion = 3; startTime = millis(); while(true) { // 接地判定まで待機 sendR(xZero, zZero); if(stateJudge == 1 || millis() - startTime > 1000){ break; } } Motion = 4; stateJudge = 0; }else if(Motion == 4){ sendR(xZero, zZero); Motion = 5; time_mSt = millis(); tim = 0; }else if(Motion == 5){ tim = millis() - time_mSt; if(tim <= delay1){ sendL(xZero, zZero + dz1 / delay1 * tim); //0 -> dz1 }else{ time_mSt = millis(); tim = 0; Motion = 6; } }else if(Motion == 6 && tim <= delay2){ tim = millis() - time_mSt; sendL(xZero, zZero + dz1 - (dz1 + dz2) / delay2 * tim); //dz1 -> -dz2 }else if(Motion == 6 && tim > delay2 ){ Motion = 7; startTime = millis(); while(true) { // 接地判定まで待機 sendL(xZero, zZero); if(stateJudge == 1 || millis() - startTime > 1000){ break; } } Motion = 0; stateJudge = 0; } break; case ModeT::Ad: //前進 if(Motion == 0){ sendL(xZero + dx1, zZero); sendR(xZero - dx1, zZero); Motion = 1; time_mSt = millis(); tim = 0; }else if(Motion == 1){ tim = millis() - time_mSt; if(tim <= delay1){ sendR(xZero - dx1 - dx2 / delay1 * tim, zZero + dz1 / delay1 * tim); //0 -> dz1 }else{ time_mSt = millis(); tim = 0; Motion = 2; } }else if(Motion == 2 && tim <= delay2){ tim = millis() - time_mSt; sendL(xZero + dx1 - 2.0 * dx1 / delay2 * tim, zZero); sendR(xZero - dx1 - dx2 + (2.0 * dx1 + dx2) / delay2 * tim, zZero + dz1 - (dz1 + dz2) / delay2 * tim); //dz1 -> -dz2 }else if(Motion == 2 && tim > delay2){ Motion = 3; startTime = millis(); while(true) { // 接地判定まで待機 sendL(xZero - dx1, zZero); sendR(xZero + dx1, zZero); if(stateJudge == 1 || millis() - startTime > 1000){ break; } } Motion = 4; stateJudge = 0; }else if(Motion == 4){ sendL(xZero - dx1, zZero); sendR(xZero + dx1, zZero); Motion = 5; time_mSt = millis(); tim = 0; }else if(Motion == 5){ tim = millis() - time_mSt; if(tim <= delay1){ sendL(xZero - dx1 - dx2 / delay1 * tim, zZero + dz1 / delay1 * tim); //0 -> dz1 }else{ time_mSt = millis(); tim = 0; Motion = 6; } }else if(Motion == 6 && tim <= delay2){ tim = millis() - time_mSt; sendL(xZero - dx1 - dx2 + (2.0 * dx1 + dx2) / delay2 * tim, zZero + dz1 - (dz1 + dz2) / delay2 * tim); //dz1 -> -dz2 sendR(xZero + dx1 - 2.0 * dx1 / delay2 * tim, zZero); }else if(Motion == 6 && tim > delay2 ){ Motion = 7; startTime = millis(); while(true) { // 接地判定まで待機 sendL(xZero + dx1, zZero); sendR(xZero - dx1, zZero); if(stateJudge == 1 || millis() - startTime > 1000){ break; } } Motion = 0; stateJudge = 0; } break; case ModeT::Back: //後進 if(Motion == 0){ sendL(xZero - dx1, zZero); sendR(xZero + dx1, zZero); Motion = 1; time_mSt = millis(); tim = 0; }else if(Motion == 1){ tim = millis() - time_mSt; if(tim <= delay1){ sendR(xZero + dx1 + dx2 / delay1 * tim, zZero + dz1 / delay1 * tim); //0 -> dz1 }else{ time_mSt = millis(); tim = 0; Motion = 2; } }else if(Motion == 2 && tim <= delay2){ tim = millis() - time_mSt; sendL(xZero - dx1 + 2.0 * dx1 / delay2 * tim, zZero); sendR(xZero + dx1 + dx2 - (2.0 * dx1 + dx2) / delay2 * tim, zZero + dz1 - (dz1 + dz2) / delay2 * tim); //dz1 -> -dz2 }else if(Motion == 2 && tim > delay2){ Motion = 3; startTime = millis(); while(true) { // 接地判定まで待機 sendL(xZero + dx1, zZero); sendR(xZero - dx1, zZero); if(stateJudge == 1 || millis() - startTime > 1000){ break; } } Motion = 4; stateJudge = 0; }else if(Motion == 4){ sendL(xZero + dx1, zZero); sendR(xZero - dx1, zZero); Motion = 5; time_mSt = millis(); tim = 0; }else if(Motion == 5){ tim = millis() - time_mSt; if(tim <= delay1){ sendL(xZero + dx1 + dx2 / delay1 * tim, zZero + dz1 / delay1 * tim); //0 -> dz1 }else{ time_mSt = millis(); tim = 0; Motion = 6; } }else if(Motion == 6 && tim <= delay2){ tim = millis() - time_mSt; sendL(xZero + dx1 + dx2 - (2.0 * dx1 + dx2) / delay2 * tim, zZero + dz1 - (dz1 + dz2) / delay2 * tim); //dz1 -> -dz2 sendR(xZero - dx1 + 2.0 * dx1 / delay2 * tim, zZero); }else if(Motion == 6 && tim > delay2 ){ Motion = 7; startTime = millis(); while(true) { // 接地判定まで待機 sendL(xZero - dx1, zZero); sendR(xZero + dx1, zZero); if(stateJudge == 1 || millis() - startTime > 1000){ break; } } Motion = 0; stateJudge = 0; } break; default: // Idle 初期姿勢 Motion = 0; for(int i = 0; i < 5; i++){ sendL(xZero, zZero); sendR(xZero, zZero); delay(20); } break; } } //Core0 void display(void *pvParameters) { M5.IMU.Init(); //フルスケールレンジ M5.IMU.SetAccelFsr(M5.IMU.AFS_2G); M5.IMU.SetGyroFsr(M5.IMU.GFS_250DPS); get_theta(); kalmanX.setAngle(theta_X); kalmanY.setAngle(theta_Y); M5.dis.setBrightness(20); WiFi.softAP(ssid, pass); // SSIDとパスの設定 delay(100); // 追記:このdelayを入れないと失敗する場合がある WiFi.softAPConfig(ip, ip, subnet); // IPアドレス、ゲートウェイ、サブネットマスクの設定 IPAddress myIP = WiFi.softAPIP(); // WiFi.softAPIP()でWiFi起動 server.on("/", handleRoot); server.on("/x0M", x0M); server.on("/x0P", x0P); server.on("/dx1M", dx1M); server.on("/dx1P", dx1P); server.on("/dx2M", dx2M); server.on("/dx2P", dx2P); server.on("/z0M", z0M); server.on("/z0P", z0P); server.on("/dz1M", dz1M); server.on("/dz1P", dz1P); server.on("/dz2M", dz2M); server.on("/dz2P", dz2P); server.on("/delay1M", d1M); server.on("/delay1P", d1P); server.on("/delay2M", d2M); server.on("/delay2P", d2P); server.on("/KpM", KpM); server.on("/KpP", KpP); server.on("/KdM", KdM); server.on("/KdP", KdP); server.on("/thM", thM); server.on("/thP", thP); server.on("/tfM", tfM); server.on("/tfP", tfP); server.on("/offsetXP", offsetXP); server.on("/offsetXM", offsetXM); server.on("/offsetYP", offsetYP); server.on("/offsetYM", offsetYM); server.begin(); twai_general_config_t g_config = { .mode = TWAI_MODE_NORMAL, .tx_io = (gpio_num_t)19, .rx_io = (gpio_num_t)22, .clkout_io = TWAI_IO_UNUSED, .bus_off_io = TWAI_IO_UNUSED, .tx_queue_len = 5, .rx_queue_len = 5, .alerts_enabled = TWAI_ALERT_NONE, .clkout_divider = 0, .intr_flags = ESP_INTR_FLAG_LEVEL1 }; //twai_timing_config_t t_config = TWAI_TIMING_CONFIG_500KBITS(); twai_timing_config_t t_config = TWAI_TIMING_CONFIG_1MBITS(); twai_filter_config_t f_config = TWAI_FILTER_CONFIG_ACCEPT_ALL(); if (twai_driver_install(&g_config, &t_config, &f_config) == ESP_OK) { Serial.println("TWAI Driver installed"); } else { Serial.println("TWAI Driver install failed"); } if (twai_start() == ESP_OK) { Serial.println("TWAI Started"); } else { Serial.println("TWAI Start failed"); } for (;;){ server.handleClient(); //LED表示 M5.dis.clear(); if(kalAngleX > 20.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i, 0xff0000); } }else if(kalAngleX <= 20.0 && kalAngleX > 12.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i, 0x0000ff); } }else if(kalAngleX <= 12.0 && kalAngleX > 4.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 5, 0x0000ff); } }else if(kalAngleX <= 4.0 && kalAngleX > 1.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 10, 0x0000ff); } }else if(abs(kalAngleX) <= 1.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 10, 0x00ff00); } }else if(kalAngleX >= -4.0 && kalAngleX < -1.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 10, 0x0000ff); } }else if(kalAngleX >= -12.0 && kalAngleX < -4.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 15, 0x0000ff); } }else if(kalAngleX >= -20.0 && kalAngleX < -12.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 20, 0x0000ff); } }else if(kalAngleX < -20.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i + 20, 0xff0000); } } if(kalAngleY > 20.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5, 0xff0000); } }else if(kalAngleY <= 20.0 && kalAngleY > 12.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5, 0x0000ff); } }else if(kalAngleY <= 12.0 && kalAngleY > 4.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 1, 0x0000ff); } }else if(kalAngleY <= 4.0 && kalAngleY > 1.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 2, 0x0000ff); } }else if(abs(kalAngleY) <= 1.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 2, 0x00ff00); } }else if(kalAngleY >= -4.0 && kalAngleY < -1.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 2, 0x0000ff); } }else if(kalAngleY >= -12.0 && kalAngleY < -4.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 3, 0x0000ff); } }else if(kalAngleY >= -20.0 && kalAngleY < -12.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 4, 0x0000ff); } }else if(kalAngleY < -20.0){ for(int i = 0; i < 5; i++){ M5.dis.drawpix(i * 5 + 4, 0xff0000); } } nowTime = micros(); loopTime = nowTime - oldTime; oldTime = nowTime; dt = (float)loopTime / 1000000.0; //sec get_theta(); get_gyro_data(); //カルマンフィルタ 姿勢 傾き kalAngleX = kalmanX.getAngle(theta_X, theta_Xdot, dt); kalAngleY = kalmanY.getAngle(theta_Y, theta_Ydot, dt); //カルマンフィルタ 姿勢 角速度 kalAngleDotX = kalmanX.getRate(); kalAngleDotY = kalmanY.getRate(); //ロール軸send rollVal = Kp * kalAngleY + Kd * kalAngleDotY; sendRoll(rollVal - rollCtrlL, rollVal - rollCtrlR); //足トルク受信 if (twai_receive(&rx_msg, 0) == ESP_OK) { if (rx_msg.identifier == 0x211 && rx_msg.data_length_code == 4) { memcpy(&torqueL, &rx_msg.data[0], 4); }else if (rx_msg.identifier == 0x212 && rx_msg.data_length_code == 4) { memcpy(&torqueR, &rx_msg.data[0], 4); } currentTorque = filter(torqueL - torqueR); diffTorque = currentTorque - preTorque; if(diffTorque > th && Motion == 7 && stateJudge == 0){ stateJudge = 1; }else if(diffTorque < -th && Motion == 3 && stateJudge == 0){ stateJudge = 1; } preTorque = currentTorque; } disableCore0WDT(); } } //ブラウザ表示 void handleRoot() { String temp ="<!DOCTYPE html> \n<html lang=\"ja\">"; temp +="<head>"; temp +="<meta charset=\"utf-8\">"; temp +="<title>ATOM</title>"; temp +="<meta name=\"viewport\" content=\"width=device-width, initial-scale=1\">"; temp +="<style>"; temp +=".container{"; temp +=" max-width: 500px;"; temp +=" margin: auto;"; temp +=" text-align: center;"; temp +=" font-size: 1.2rem;"; temp +="}"; temp +="span,.pm{"; temp +=" display: inline-block;"; temp +=" border: 1px solid #ccc;"; temp +=" width: 50px;"; temp +=" height: 30px;"; temp +=" vertical-align: middle;"; temp +=" margin-bottom: 20px;"; temp +="}"; temp +="span{"; temp +=" width: 120px;"; temp +="}"; temp +="button{"; temp +=" width: 100px;"; temp +=" height: 40px;"; temp +=" font-weight: bold;"; temp +=" margin-bottom: 20px;"; temp +="}"; temp +="button.on{ background:lime; color:white; }"; temp +=".column-3{ max-width:330px; margin:auto; text-align:center; display:flex; justify-content:space-between; flex-wrap:wrap; }"; temp +="</style>"; temp +="</head>"; temp +="<body>"; temp +="<div class=\"container\">"; temp +="<h3>ATOM</h3>"; //dx1 temp +="dx1 <br>"; temp +="<a class=\"pm\" href=\"/dx1M\">-</a>"; temp +="<span>" + String(dx1) + "</span>"; temp +="<a class=\"pm\" href=\"/dx1P\">+</a><br>"; //dx2 temp +="dx2 <br>"; temp +="<a class=\"pm\" href=\"/dx2M\">-</a>"; temp +="<span>" + String(dx2) + "</span>"; temp +="<a class=\"pm\" href=\"/dx2P\">+</a><br>"; //dz1 temp +="dz1 <br>"; temp +="<a class=\"pm\" href=\"/dz1M\">-</a>"; temp +="<span>" + String(dz1) + "</span>"; temp +="<a class=\"pm\" href=\"/dz1P\">+</a><br>"; //dz2 temp +="dz2 <br>"; temp +="<a class=\"pm\" href=\"/dz2M\">-</a>"; temp +="<span>" + String(dz2) + "</span>"; temp +="<a class=\"pm\" href=\"/dz2P\">+</a><br>"; //delay1 temp +="delay1<br>"; temp +="<a class=\"pm\" href=\"/delay1M\">-</a>"; temp +="<span>" + String(delay1) + "</span>"; temp +="<a class=\"pm\" href=\"/delay1P\">+</a><br>"; //delay2 temp +="delay2<br>"; temp +="<a class=\"pm\" href=\"/delay2M\">-</a>"; temp +="<span>" + String(delay2) + "</span>"; temp +="<a class=\"pm\" href=\"/delay2P\">+</a><br>"; //初期姿勢x temp +="x0 <br>"; temp +="<a class=\"pm\" href=\"/x0M\">-</a>"; temp +="<span>" + String(xZero) + "</span>"; temp +="<a class=\"pm\" href=\"/x0P\">+</a><br>"; //初期姿勢z temp +="z0 <br>"; temp +="<a class=\"pm\" href=\"/z0M\">-</a>"; temp +="<span>" + String(zZero) + "</span>"; temp +="<a class=\"pm\" href=\"/z0P\">+</a><br>"; //Kp temp +="Kp<br>"; temp +="<a class=\"pm\" href=\"/KpM\">-</a>"; temp +="<span>" + String(Kp) + "</span>"; temp +="<a class=\"pm\" href=\"/KpP\">+</a><br>"; //Kd temp +="Kd<br>"; temp +="<a class=\"pm\" href=\"/KdM\">-</a>"; temp +="<span>" + String(Kd) + "</span>"; temp +="<a class=\"pm\" href=\"/KdP\">+</a><br>"; //th temp +="th<br>"; temp +="<a class=\"pm\" href=\"/thM\">-</a>"; temp +="<span>" + String(th) + "</span>"; temp +="<a class=\"pm\" href=\"/thP\">+</a><br>"; //tf temp +="LPF Tf <br>"; temp +="<a class=\"pm\" href=\"/tfM\">-</a>"; temp +="<span>" + String(tf) + "</span>"; temp +="<a class=\"pm\" href=\"/tfP\">+</a><br>"; //offsetX temp += "offsetX<br>"; temp += "<a class=\"pm\" href=\"/offsetXM\">-</a>"; temp += "<span>" + String(offsetX) + "</span>"; temp += "<a class=\"pm\" href=\"/offsetXP\">+</a><br>"; //offsetY temp += "offsetY<br>"; temp += "<a class=\"pm\" href=\"/offsetYM\">-</a>"; temp += "<span>" + String(offsetY) + "</span>"; temp += "<a class=\"pm\" href=\"/offsetYP\">+</a><br>"; temp +="</div>"; temp +="</body>"; server.send(200, "text/HTML", temp); } void x0M() { if(xZero > -150.0){ xZero -= 1.0; preferences.putFloat("xZero", xZero ); } handleRoot(); } void x0P() { if(xZero < 150.0){ xZero += 1.0; preferences.putFloat("xZero", xZero ); } handleRoot(); } void dx1M() { if(dx1 > -100.0){ dx1 -= 1.0; preferences.putFloat("dx1", dx1); } handleRoot(); } void dx1P() { if(dx1 < 100.0){ dx1 += 1.0; preferences.putFloat("dx1", dx1); } handleRoot(); } void dx2M() { if(dx2 > -100.0){ dx2 -= 1.0; preferences.putFloat("dx2", dx2); } handleRoot(); } void dx2P() { if(dx2 < 100.0){ dx2 += 1.0; preferences.putFloat("dx2", dx2); } handleRoot(); } void z0M() { if(zZero > 0.0){ zZero -= 1.0; preferences.putFloat("zZero", zZero ); } handleRoot(); } void z0P() { if(zZero < 150.0){ zZero += 1.0; preferences.putFloat("zZero", zZero ); } handleRoot(); } void dz1M() { if(dz1 > 0.0){ dz1 -= 0.5; preferences.putFloat("dz1", dz1 ); } handleRoot(); } void dz1P() { if(dz1 < 100.0){ dz1 += 0.5; preferences.putFloat("dz1", dz1 ); } handleRoot(); } void dz2M() { if(dz2 > 0.0){ dz2 -= 0.5; preferences.putFloat("dz2", dz2 ); } handleRoot(); } void dz2P() { if(dz2 < 100.0){ dz2 += 0.5; preferences.putFloat("dz2", dz2 ); } handleRoot(); } void d1M() { if(delay1 > 0){ delay1 -= 5; preferences.putInt("delay1", delay1); } handleRoot(); } void d1P() { if(delay1 <= 1000){ delay1 += 5; preferences.putInt("delay1", delay1); } handleRoot(); } void d2M() { if(delay2 > 0){ delay2 -= 5; preferences.putInt("delay2", delay2); } handleRoot(); } void d2P() { if(delay2 <= 1000){ delay2 += 5; preferences.putInt("delay2", delay2); } handleRoot(); } void KpM() { if(Kp > -10.0){ Kp -= 0.1; preferences.putFloat("Kp", Kp); } handleRoot(); } void KpP() { if(Kp <= 10.0){ Kp += 0.1; preferences.putFloat("Kp", Kp); } handleRoot(); } void KdM() { if(Kd > -10.0){ Kd -= 0.01; preferences.putFloat("Kd", Kd); } handleRoot(); } void KdP() { if(Kd <= 10.0){ Kd += 0.01; preferences.putFloat("Kd", Kd); } handleRoot(); } void thM() { if (th >= 0) { th -= 5.0; preferences.putFloat("th", th); } handleRoot(); } void thP() { if (th <= 100.0) { th += 5.0; preferences.putFloat("th", th); } handleRoot(); } void tfM() { if (tf >= 0.05) { tf -= 0.05; preferences.putFloat("tf", tf); filter.Tf = tf; } handleRoot(); } void tfP() { if (tf <= 1.0) { tf += 0.05; preferences.putFloat("tf", tf); filter.Tf = tf; } handleRoot(); } void offsetXM() { if (offsetX >= -160) { offsetX -= 0.1; preferences.putFloat("offsetX", offsetX); } handleRoot(); } void offsetXP() { if (offsetX <= 160) { offsetX += 0.1; preferences.putFloat("offsetX", offsetX); } handleRoot(); } void offsetYM() { if (offsetY >= -160) { offsetY -= 0.1; preferences.putFloat("offsetY", offsetY); } handleRoot(); } void offsetYP() { if (offsetY <= 160) { offsetY += 0.1; preferences.putFloat("offsetY", offsetY); } handleRoot(); } void setup() { M5.begin(true, true, true); //SerialEnable, bool I2CEnable, DisplayEnable Serial.println("-----------------------------"); uint8_t btmac[6]; esp_read_mac(btmac, ESP_MAC_BT); Serial.printf("[Bluetooth] Mac Address = %02X:%02X:%02X:%02X:%02X:%02X\r\n", btmac[0], btmac[1], btmac[2], btmac[3], btmac[4], btmac[5]); PS4.begin(); //パラメータ初期値取得 preferences.begin("parameter", false); Kp = preferences.getFloat("Kp", Kp); Kd = preferences.getFloat("Kd", Kd); xZero = preferences.getFloat("xZero", xZero); dx1 = preferences.getFloat("dx1", dx1); dx2 = preferences.getFloat("dx2", dx2); zZero = preferences.getFloat("zZero", zZero); dz1 = preferences.getFloat("dz1", dz1); dz2 = preferences.getFloat("dz2", dz2); delay1 = preferences.getInt("delay1", delay1); delay2 = preferences.getInt("delay2", delay2); th = preferences.getFloat("th", th); tf = preferences.getFloat("tf", tf); filter.Tf = tf; offsetX = preferences.getFloat("offsetX", offsetX); offsetY = preferences.getFloat("offsetY", offsetY); //core0 タスク xTaskCreatePinnedToCore( display , "display" // A name just for humans , 4096 // This stack size can be checked & adjusted by reading the Stack Highwater , NULL , 1 // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest. , NULL , 0); } void loop(){ if (PS4.isConnected()) { //PS4コントローラ int currentLStickX = PS4.LStickX(); int currentLStickY = PS4.LStickY(); int currentRStickX = PS4.RStickX(); int currentRStickY = PS4.RStickY(); if (currentLStickX != lastLStickX || currentLStickY != lastLStickY) { float Lx = PS4.LStickX() / 4.0; float Ly = PS4.LStickY() / 3.0; sendL(-Lx + xZero, Ly + zZero); sendR(Lx + xZero, Ly + zZero); lastLStickX = currentLStickX; lastLStickY = currentLStickY; }else if (currentRStickX != lastRStickX || currentRStickY != lastRStickY) { rollCtrlL = PS4.RStickX() / 10.0; rollCtrlR = rollCtrlL; lastRStickX = currentRStickX; lastRStickY = currentRStickY; }else if (PS4.Up()) { setMotion(ModeT::Ad); idleState = 0; }else if (PS4.Down()) { setMotion(ModeT::Back); idleState = 0; }else if (PS4.Cross()) { setMotion(ModeT::Step); idleState = 0; }else if(idleState == 0){ setMotion(ModeT::Idle); idleState = 1; } }else { setMotion(ModeT::Idle); } } |
動作モードを enum class ModeT (L. 1, 131) で定義して、setMotion() 関数内 (L. 134~337)で動作を切り替えています。
モードは以下の4種でPS4コントローラで切り替えます (L. 996~1011)。
- Idle:初期姿勢 (x0 = 10mm, z0 = 99mm)
- Step:足踏み ×ボタン
- Ad:前進 十字キー 上ボタン
- Back:後進 十字キー 下ボタン
足踏み、前後進の動作詳細は次節以降で説明します。
足運動時のウェイトシフトや足底地面接地をモータトルク値(電流値)の検知で実施します (L. 536~553) 。詳細は次節。
CAN ID 0x211:左足下腿モータのトルク受信
CAN ID 0x212:右足下腿モータのトルク受信
トルク(モータ負荷電流)の生データにはノイズが乗っているためSimpleFOCのLPFライブラリを使用してフィルタリングしています (L.10, 36~41, 544)。
tf:時定数(応答の遅さ)
tfを大きくすると → 出力はなめらかになるが応答が遅れる
tfを小さくすると → 応答は速いがノイズが残る
書き込み
ATOM Matrixに書き込む際にはモータに給電しないようにATOMの電源ラインは外してください。
ボードは”M5Stack-ATOM”を選択
PS4Controllerライブラリのサイズが大きいのでPartition Schemeは”No OTA (Large APP)”を選択
ブラウザアプリ
ATOM MatrixのAPモードでWiFi接続してブラウザから各種パラメータを指定します。
-
スマホもしくはPCのWiFi接続設定でSSID ”ATOM”に接続
パスワード:password -
ブラウザで”192.168.22.90”にアクセス
dx1:歩行時の歩幅指定 [mm]
dx2:歩行時の足蹴り上げ前後方向の幅 [mm]
dz1:歩行時の足蹴り上げ高さ [mm]
dz2:足上げ高さ [mm]
delay1:足蹴り上げ時間 [msec]
delay2:足上げ時間 [msec]
th:トルク接地判定しきい値
tf:トルクLPF 時定数
動作
起動後、PS4コントローラと同期して動作を楽しめます。
予算3万円でつくる BLDC 2足歩行ロボット pic.twitter.com/W8Q25QgzR8
— HomeMadeGarbage (@H0meMadeGarbage) September 13, 2025
足踏み
8つのMotionステートで足踏み動作を実現しています。
Motion番号 | 動作内容 | 補間 or 待機 | 条件・遷移先 |
0 | 左足を初期姿勢 (x0, z0) に戻す | 即時 | Motion = 1 |
1 | 右足を蹴り下げる (0 → dz1) | delay1 [ms]でリニア補間 | 終了後 Motion = 2 |
2 | 右足を上げる (dz1 → -dz2) | delay2 [ms]でリニア補間 | 終了後 Motion = 3 |
3 | 右足接地待ち | (x0, z0) に保持 | 接地検出(stateJudge==1) または 1秒経過 → Motion = 4 |
4 | 右足を初期姿勢 (x0, z0) に戻す | 即時 | Motion = 5 |
5 | 左足を蹴り下げる (0 → dz1) | delay1 [ms]でリニア補間 | 終了後 Motion = 6 |
6 | 左足を上げる (dz1 → -dz2) | delay2 [ms]でリニア補間 | 終了後 Motion = 7 |
7 | 左足接地待ち | (x0, z0) に保持 | 接地検出(stateJudge==1) または 1秒経過 → Motion = 0 |
足上げは事前に地面を蹴ってから実施することで、足上げ高さを稼いています。
要するに蹴りでウェイトシフトを容易にしています。
左右動作の切り替えは足モータのトルクによる足底地面接地検知で実施しています。
左右の下腿モータトルクをCAN通信で受信しています。
左右のトルクの差で接地を検出
予算3万円でつくる BLDC 2足歩行ロボット
モータトルクの差で接地を検知 pic.twitter.com/ltoNLrhoLB— HomeMadeGarbage (@H0meMadeGarbage) September 14, 2025
ここでは左右のトルク差の変化分をしきい値として接地判定しています。
変化分で判定することで地面の凸凹の影響を低減しています。
動作
PS4コントローラの×ボタンで足踏みします。
モータトルク検知による見事な接地検出で
こんなにも元気でスムーズな足踏みが実現 pic.twitter.com/th1W8jHXWg— HomeMadeGarbage (@H0meMadeGarbage) September 14, 2025
転ばないように蹴り上げ量 (dz1)や蹴り上げ時間 (delay1) と
足上げ量 (dz2)や足上げ時間 (delay2) をうまく調整してください。
前後進
足踏み動作に前後方向動作を組み合わせて前後進を実現します。
前進時のステートは以下の通り
Motion | x方向の動作 | z方向の動作 | 補間 or 待機 | 遷移条件 |
0 | 左足:x0 + dx1 右足:x0 – dx1 |
両足とも z0 | 即時 | Motion = 1 |
1 | 右足:-dx1 → -dx1 – dx2 |
右足:0 → +dz1 |
delay1で補間 | 終了後 Motion=2 |
2 |
左足:+dx1 → -dx1 |
左足: z0 固定 右足:+dz1 → -dz2 |
delay2で補間 | 終了後 Motion=3 |
3 | 左足:x0 – dx1 右足:x0 + dx1 |
両脚とも z0 | 固定 | 接地検出(stateJudge==1) または 1秒経過 → Motion = 4 |
4 | 左足:x0 – dx1 右足:x0 + dx1 |
両脚とも z0 | 即時 | Motion=5 |
5 | 左足:-dx1 → -dx1 – dx2 | 左足:0 → +dz1 | delay1で補間 | 終了後 Motion=6 |
6 | 左足:-dx1 – dx2 → +dx1 右足:+dx1 → -dx1 |
左足:+dz1 → -dz2 右足:z0 固定 |
delay2で補間 | 終了後 Motion=7 |
7 | 左足:x0 + dx1 右足:x0 – dx1 |
両脚とも zZero | 固定 | 接地検出(stateJudge==1) または 1秒経過 → Motion = 0 |
地面を蹴る際にdx2で進行方向と逆に斜めにすることで推進力を与えています。
dx1が前後の移動量で1歩の歩幅は2 × dx1 となります。
後進はx方向を反転して実現。
動作
PS4コントローラ十字キーの上下ボタンで前後進します。
予算3万円でつくる BLDC 2足歩行ロボット
前後進 pic.twitter.com/2nmLaxqmgp— HomeMadeGarbage (@H0meMadeGarbage) September 14, 2025
演習問題
1-パラメータ調整
ATOM Matrixのブラウザアプリやコードを修正するなどして歩行パラメータ値を変更して動作にどう影響するのか体験してみよう。
2-動作検討
次回は旋回動作や横移動、ジャンプを紹介します。
予習として事前に動作を考えてみましょう。
おわりに
本号では2足歩行ロボット HM-01 の足踏み・歩行動作を楽しみました。
上手にウェイトシフトして ちょこまか歩いて可愛いです。
次回はさらに歩行をアレンジして旋回や横移動を楽しみたいと思います。
加えてBLDCの即効性を活用してジャンプ動作にも挑戦します。