{"id":216,"date":"2021-06-10T18:35:19","date_gmt":"2021-06-10T09:35:19","guid":{"rendered":"https:\/\/rfsec.ddns.net\/db\/?p=216"},"modified":"2021-06-25T15:56:34","modified_gmt":"2021-06-25T06:56:34","slug":"esp32-dc%e3%83%a2%e3%83%bc%e3%82%bf-websocket-ui%e3%81%a7%e5%80%92%e7%ab%8b%e6%8c%af%e5%ad%90","status":"publish","type":"post","link":"https:\/\/rfsec.ddns.net\/db\/?p=216","title":{"rendered":"ESP32\/DC\u30e2\u30fc\u30bf\/Websocket UI\u3067\u5012\u7acb\u632f\u5b50"},"content":{"rendered":"\n<p>PID\u5236\u5fa1\u306e\u30d1\u30e9\u30e1\u30fc\u30bf\u3068\u81ea\u7acb\u306e\u305f\u3081\u306e\u76ee\u6a19\u89d2\u5ea6\uff08TARGET)\u3092Websocket UI\u3067\u30b9\u30de\u30db\u304b\u3089\u8a2d\u5b9a\u3057\u307e\u3059\u3002\u4eca\u306e\u3068\u3053\u308d\u3001\u30d1\u30e9\u30e1\u30fc\u30bf\u306e\u5024\u304c\u9069\u5207\u3067\u306a\u3044\u3088\u3046\u3067\u3001\u786c\u3044\u5e8a\u9762\u4e0a\u3067\u306f\u77ed\u6642\u9593\u3067\u5012\u308c\u307e\u3059\u3002\u3084\u308f\u3089\u304b\u3044\u7d20\u6750\u306e\u4e0a\u3067\u306f\u5012\u308c\u306a\u3044\u306e\u3067\u3001\u3053\u306e\u72b6\u614b\u3067\u9069\u5207\u306a\u30d1\u30e9\u30e1\u30fc\u30bf\u3092\u8a66\u884c\u932f\u8aa4\u3067\u63a2\u7d22\u4e2d\u3001\u3001\u3001Web\u30d9\u30fc\u30b9\u306eUI\u306e\u305f\u3081\u304b\u3001\u7d30\u304b\u306a\u30d1\u30e9\u30e1\u30fc\u30bf\u8a2d\u5b9a\u306e\u64cd\u4f5c\u6027\u304c\u3044\u307e\u3044\u3061\u306a\u306e\u3067\u3001\u6539\u5584\u304c\u5fc5\u8981\u304b\u3082\u3057\u308c\u306a\u3044\u3002<\/p>\n\n\n\n<figure class=\"wp-block-embed is-type-video is-provider-youtube wp-block-embed-youtube wp-embed-aspect-16-9 wp-has-aspect-ratio\"><div class=\"wp-block-embed__wrapper\">\n<iframe loading=\"lazy\" title=\"ESP32-MPU5060-Websocket\" width=\"625\" height=\"352\" src=\"https:\/\/www.youtube.com\/embed\/PgDsecsJ_nc?feature=oembed\" frameborder=\"0\" allow=\"accelerometer; autoplay; clipboard-write; encrypted-media; gyroscope; picture-in-picture; web-share\" referrerpolicy=\"strict-origin-when-cross-origin\" allowfullscreen><\/iframe>\n<\/div><figcaption><br><\/figcaption><\/figure>\n\n\n\n<p><em>\u5012\u7acb\u632f\u5b50\u306e\u30b3\u30fc\u30c9\u306f\u3001<\/em><a rel=\"noreferrer noopener\" href=\"https:\/\/qiita.com\/Google_Homer\/items\/3897e7ffef9d247e2f56\" target=\"_blank\">https:\/\/qiita.com\/Google_Homer\/items\/3897e7ffef9d247e2f56<\/a><em>\u3000\u3092\u53c2\u8003\u306b<\/em>\u3057\u3066\u3044\u307e\u3059\u3002<\/p>\n\n\n\n<p>Websocket\u306e\u30b3\u30fc\u30c9\u306f\u3001https:\/\/github.com\/mgo-tec\/ESP32_SPIFFS_EasyWebSocket\u3000\u3092\u53c2\u8003\u306b\u3057\u3066\u3044\u307e\u3059\u3002<\/p>\n\n\n\n<div class=\"hcb_wrap\"><pre class=\"prism line-numbers lang-cpp\" data-lang=\"C++\"><code>#include &lt;WiFi.h&gt;\n#include &lt;WiFiMulti.h&gt;\n#include &quot;ESP32_SPIFFS_EasyWebSocket.h&quot; \/\/beta ver 1.60\n\n#include &lt;MadgwickAHRS.h&gt;\nMadgwick MadgwickFilter;\n#include &quot;I2Cdev.h&quot;\n#define MPU6050_PWR_MGMT_1   0x6B\n#define MPU_ADDRESS  0x68\n\n#include &quot;Wire.h&quot;\n#include &lt;SPI.h&gt;\n#include &lt;Adafruit_GFX.h&gt;\n#include &lt;Adafruit_SSD1306.h&gt;\n#define SCREEN_WIDTH 128 \/\/ OLED display width, in pixels\n#define SCREEN_HEIGHT 64 \/\/ OLED display height, in pixels\n#define OLED_RESET     4 \/\/ Reset pin # (or -1 if sharing Arduino reset pin)\n#define SCREEN_ADDRESS 0x3C \/\/\/&lt; See datasheet for Address; 0x3D for 128x64, 0x3C for 128x32\nAdafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);\n\n\/\/PID\u30d1\u30e9\u30e1\u30fc\u30bf\u8abf\u6574\n\/\/PID\u4fc2\u6570\n\/\/#define TARGET            0.4\n\/\/#define KP                100.0\n\/\/#define KI                2.0\n\/\/#define KD                2.0\n\n\/\/Motor\n#define LED_PIN            27                      \/\/ \u5185\u8535LED\n#define MOTOR_PIN_F        A4                      \/\/ to DC Motor Driver FIN\n#define MOTOR_PIN_R        A18                      \/\/ to DC Motor Driver RIN\n#define MOTOR_PWM_F        0                       \/\/ PWM CHANNEL\n#define MOTOR_PWM_R        1                       \/\/ PWM CHANNEL\n#define MOTOR_POWER_MIN    50\nint MOTOR_POWER_MAX = 200;\n\n#define DPS                1000                    \/\/ Gscale [deg\/s]\n\nconst char* ssid = &quot;\uff0a\uff0a\uff0a\uff0a\uff0a\uff0a\uff0a&quot;; \/\/\u3054\u81ea\u5206\u306e\u30eb\u30fc\u30bf\u30fc\u306eSSID\u306b\u66f8\u304d\u63db\u3048\u3066\u304f\u3060\u3055\u3044\nconst char* password = &quot;\uff0a\uff0a\uff0a\uff0a\uff0a\uff0a&quot;; \/\/\u3054\u81ea\u5206\u306e\u30eb\u30fc\u30bf\u30fc\u306e\u30d1\u30b9\u30ef\u30fc\u30c9\u306b\u66f8\u304d\u63db\u3048\u3066\u304f\u3060\u3055\u3044\n\nconst char* HTM_head_file1 = &quot;\/EWS\/LIPhead1.txt&quot;; \/\/HTML\u30d8\u30c3\u30c0\u30d5\u30a1\u30a4\u30eb1\nconst char* HTM_head_file2 = &quot;\/EWS\/LIPhead2.txt&quot;; \/\/HTML\u30d8\u30c3\u30c0\u30d5\u30a1\u30a4\u30eb2\nconst char* HTML_body_file = &quot;\/EWS\/dummy.txt&quot;; \/\/HTML body\u8981\u7d20\u30d5\u30a1\u30a4\u30eb\uff08\u3053\u3053\u3067\u306f\u30c0\u30df\u30fc\u30d5\u30a1\u30a4\u30eb\u3068\u3057\u3066\u304a\u304f\uff09\nconst char* dummy_file = &quot;\/EWS\/dummy.txt&quot;; \/\/HTML\u30d5\u30a1\u30a4\u30eb\u9023\u7d50\u306e\u305f\u3081\u306e\u30c0\u30df\u30fc\u30d5\u30a1\u30a4\u30eb\n\nESP32_SPIFFS_EasyWebSocket ews;\nWiFiMulti wifiMulti;\n\nIPAddress LIP; \/\/\u30ed\u30fc\u30ab\u30ebIP\u30a2\u30c9\u30ec\u30b9\u81ea\u52d5\u53d6\u5f97\u7528\n\nString ret_str; \/\/\u30d6\u30e9\u30a6\u30b6\u304b\u3089\u9001\u3089\u308c\u3066\u304f\u308b\u6587\u5b57\u5217\u683c\u7d0d\u7528\nString txt = &quot;text send?&quot;; \/\/\u30d6\u30e9\u30a6\u30b6\u304b\u3089\u53d7\u4fe1\u3057\u305f\u6587\u5b57\u5217\u3092 ESP32\u304b\u3089\u518d\u9001\u4fe1\u3059\u308b\u6587\u5b57\u5217\n\nint PingSendTime = 10000; \/\/ESP32\u304b\u3089\u30d6\u30e9\u30a6\u30b6\u3078Ping\u9001\u4fe1\u3059\u308b\u9593\u9694(ms)\n\nlong ESP32_send_LastTime;\nint ESP32_send_Rate = 300;\nbyte cnt = 0;\n\n\/\/PID\nfloat power = 0, I = 0, preP = 0, preTime;\nfloat now = 0, Duty = 0, pitch, roll, yaw;\nfloat KP = 100.0, KI = 2.0, KD = 2.0, TARGET = 0.0;\nboolean f_disp = false;\n\nvoid setup() {\n  Wire.begin();\n  Serial.begin(38400);\n  Wire.beginTransmission(MPU_ADDRESS);\n  Wire.write(MPU6050_PWR_MGMT_1);  \/\/MPU6050_PWR_MGMT_1\u30ec\u30b8\u30b9\u30bf\u306e\u8a2d\u5b9a\n  Wire.write(0x00);\n  Wire.endTransmission();\n\n  Serial.print(F(&quot;Connecting to &quot;));\n  Serial.println(ssid);\n\n  wifiMulti.addAP(ssid, password);\n\n  Serial.println(F(&quot;Connecting Wifi...&quot;));\n  if (wifiMulti.run() == WL_CONNECTED) {\n    Serial.println(&quot;&quot;);\n    Serial.println(F(&quot;WiFi connected&quot;));\n    Serial.println(F(&quot;IP address: &quot;));\n    LIP = WiFi.localIP(); \/\/ESP32\u306e\u30ed\u30fc\u30ab\u30ebIP\u30a2\u30c9\u30ec\u30b9\u3092\u81ea\u52d5\u53d6\u5f97\n    Serial.println(WiFi.localIP());\n  }\n  ews.EWS_server_begin();\n  Serial.println(); Serial.println(&quot;Initializing SPIFFS ...&quot;);\n\n  if (!SPIFFS.begin()) {\n    Serial.println(&quot;SPIFFS failed, or not present&quot;);\n    return;\n  }\n\n  Serial.println(&quot;SPIFFS initialized. OK!&quot;);\n  MadgwickFilter.begin(100); \/\/100Hz\n  \/\/ SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally\n  if (!display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {\n    Serial.println(F(&quot;SSD1306 allocation failed&quot;));\n    for (;;); \/\/ Don&#39;t proceed, loop forever\n  }\n  pinMode(LED_PIN, OUTPUT);\n  digitalWrite(LED_PIN, HIGH);\n  pinMode(MOTOR_PIN_F, OUTPUT);\n  pinMode(MOTOR_PIN_R, OUTPUT);\n\n  ledcSetup(MOTOR_PWM_F, 312500, 8); \/\/CHANNEL, FREQ, BIT\n  ledcSetup(MOTOR_PWM_R, 312500, 8);\n  ledcAttachPin(MOTOR_PIN_F, MOTOR_PWM_F);\n  ledcAttachPin(MOTOR_PIN_R, MOTOR_PWM_R);\n  \/\/ \u521d\u671f\u5316\n\n  delay(10);\n\n  \/\/ Clear the buffer\n  display.clearDisplay();\n  \/\/ \u30c6\u30ad\u30b9\u30c8\u30b5\u30a4\u30ba\u3092\u8a2d\u5b9a\n  display.setTextSize(1);\n  \/\/ \u30c6\u30ad\u30b9\u30c8\u8272\u3092\u8a2d\u5b9a\n  display.setTextColor(WHITE);\n  display.setCursor(20, 5);\n  display.println(&quot;Start...&quot;);\n  display.setCursor(20, 25);\n  display.println(WiFi.localIP());\n  display.display();\n\n  delay(10); \/\/ Pause for 2 seconds\n  preTime = micros();\n  \/\/  TaskHandle_t th; \/\/ESP32 \u30de\u30eb\u30c1\u30bf\u30b9\u30af\u3000\u30cf\u30f3\u30c9\u30eb\u5b9a\u7fa9\n  \/\/  xTaskCreatePinnedToCore(Task1, &quot;Task1&quot;, 4096, NULL, 5, &th, 0); \/\/\u30de\u30eb\u30c1\u30bf\u30b9\u30af core 0 \u5b9f\u884c\n\n  ESP32_send_LastTime = millis();\n}\n\nvoid loop() {\n  websocket_handshake();\n\n  if (ret_str != &quot;_close&quot;) {\n    if (millis() - ESP32_send_LastTime &gt; ESP32_send_Rate) {\n      if (cnt &gt; 3) {\n        cnt = 0;\n      }\n      websocket_send(cnt, txt);\n      cnt++;\n      ESP32_send_LastTime = millis();\n    }\n    ret_str = ews.EWS_ESP32CharReceive(PingSendTime);\n    if (ret_str != &quot;\\0&quot;) {\n      Serial.println(ret_str);\n      if (ret_str != &quot;Ping&quot;) {\n        if (ret_str[0] != &#39;t&#39;) {\n          int ws_data = (ret_str[0] - 0x30) * 100 + (ret_str[1] - 0x30) * 10 + (ret_str[2] - 0x30);\n          switch (ret_str[4]) {\n            case &#39;!&#39;:\n              ESP32_send_Rate = ws_data;\n              break;\n            case &#39;B&#39;:\n              TARGET = float(5.0 - ws_data \/ 20.0);\n              break;\n            case &#39;G&#39;:\n              KP = float(ws_data \/ 1.8) ;\n              break;\n            case &#39;R&#39;:\n              KI = float(ws_data \/ 50.0);\n              break;\n            case &#39;_&#39;:\n              KD = float(ws_data \/ 50.0);\n              break;\n            case &#39;A&#39;:\n              f_disp = ! f_disp;\n              break;\n            case &#39;O&#39;:\n              KP = 100, KI = 2.0, KD = 2.0, TARGET = 0.0;\n              break;\n          }\n        } else if (ret_str[0] == &#39;t&#39;) {\n          txt = ret_str.substring(ret_str.indexOf(&#39;|&#39;) + 1, ret_str.length() - 1);\n          Serial.println(txt);\n        }\n      }\n    }\n  } else if (ret_str == &quot;_close&quot;) {\n    ESP32_send_LastTime = millis();\n    ret_str = &quot;&quot;;\n  }\n  PID();\n}\n\n\/\/************* \u5012\u7acb\u632f\u308a\u5b50 ****************************************\nvoid PID() {\n  float  P, D, dt, Time;\n  static float  powerI = 0;\n\n  Wire.beginTransmission(0x68);\n  Wire.write(0x3B);\n  Wire.endTransmission(false);\n  Wire.requestFrom(0x68, 14, true);\n  while (Wire.available() &lt; 14);\n  int16_t axRaw, ayRaw, azRaw, gxRaw, gyRaw, gzRaw, Temperature;\n\n  axRaw = Wire.read() &lt;&lt; 8 | Wire.read();\n  ayRaw = Wire.read() &lt;&lt; 8 | Wire.read();\n  azRaw = Wire.read() &lt;&lt; 8 | Wire.read();\n  Temperature = Wire.read() &lt;&lt; 8 | Wire.read();\n  gxRaw = Wire.read() &lt;&lt; 8 | Wire.read();\n  gyRaw = Wire.read() &lt;&lt; 8 | Wire.read();\n  gzRaw = Wire.read() &lt;&lt; 8 | Wire.read();\n\n  \/\/ \u52a0\u901f\u5ea6\u5024\u3092\u5206\u89e3\u80fd\u3067\u5272\u3063\u3066\u52a0\u901f\u5ea6(G)\u306b\u5909\u63db\u3059\u308b\n  float acc_x = axRaw \/ 16384.0;  \/\/FS_SEL_0 16,384 LSB \/ g\n  float acc_y = ayRaw \/ 16384.0;\n  float acc_z = azRaw \/ 16384.0;\n\n  \/\/ \u89d2\u901f\u5ea6\u5024\u3092\u5206\u89e3\u80fd\u3067\u5272\u3063\u3066\u89d2\u901f\u5ea6(degrees per sec)\u306b\u5909\u63db\u3059\u308b\n  float gyro_x = gxRaw \/ 131.0;  \/\/ (\u5ea6\/s)\n  float gyro_y = gyRaw \/ 131.0;\n  float gyro_z = gzRaw \/ 131.0;\n\n  \/*\n    \/\/c.f. Madgwick\u30d5\u30a3\u30eb\u30bf\u30fc\u3092\u4f7f\u308f\u305a\u306b\u3001PRY\uff08pitch, roll, yaw\uff09\u3092\u8a08\u7b97\n    double roll  = atan2(acc_y, acc_z) * RAD_TO_DEG;\n    double pitch = atan(-acc_x \/ sqrt(acc_y * acc_y + acc_z * acc_z)) * RAD_TO_DEG;\n  *\/\n\n  \/\/Madgwick\u30d5\u30a3\u30eb\u30bf\u30fc\u3092\u7528\u3044\u3066\u3001PRY\uff08pitch, roll, yaw\uff09\u3092\u8a08\u7b97\n  MadgwickFilter.updateIMU(gyro_x, gyro_y, gyro_z, acc_x, acc_y, acc_z);\n\n  \/\/PRY\u306e\u8a08\u7b97\u7d50\u679c\u3092\u53d6\u5f97\u3059\u308b\n  roll  = MadgwickFilter.getRoll();\n  pitch = MadgwickFilter.getPitch();\n  yaw   = MadgwickFilter.getYaw();\n  now     = TARGET - roll                 ; \/\/ \u76ee\u6a19\u89d2\u5ea6\u304b\u3089\u73fe\u5728\u306e\u89d2\u5ea6\u3092\u5f15\u3044\u3066\u504f\u5dee\u3092\u6c42\u3081\u308b\n  if (f_disp) {\n    display.clearDisplay();\n    display.setCursor(20, 5);\n    display.println( roll);\n    display.setCursor(20, 25);\n    display.println( now);\n    display.display();\n  }\n  if (-20 &lt; now && now &lt; 20) {\n    Time    = micros()                    ;\n    dt      = (Time - preTime) \/ 1000000  ; \/\/ \u51e6\u7406\u6642\u9593\u3092\u6c42\u3081\u308b\n    preTime = Time                        ; \/\/ \u51e6\u7406\u6642\u9593\u3092\u8a18\u9332\n    P       = now \/ 90                    ; \/\/ -90~90\u2192-1.0~1.0\n    I      += P * dt                      ; \/\/ \u504f\u5dee\u3092\u7a4d\u5206\u3059\u308b\n    D       = (P - preP) \/ dt             ; \/\/ \u504f\u5dee\u3092\u5fae\u5206\u3059\u308b\n    preP    = P                           ; \/\/ \u504f\u5dee\u3092\u8a18\u9332\u3059\u308b\n    power  += KP * P + KI * I + KD * D    ; \/\/ \u51fa\u529b\u3092\u8a08\u7b97\u3059\u308b\n    if (power &lt; -1) power = -1            ; \/\/ \u2192-1.0~1.0\n    if (1 &lt; power)  power =  1            ;\n    \/\/Motor\u99c6\u52d5\n    Duty = (int)((MOTOR_POWER_MAX - MOTOR_POWER_MIN) * abs(power) + MOTOR_POWER_MIN);\n    ledcWrite( MOTOR_PWM_F, (power &lt; 0 ?    0 : Duty) );\n    ledcWrite( MOTOR_PWM_R, (power &lt; 0 ? Duty :    0) );\n    digitalWrite(LED_PIN, HIGH);\n    if (f_disp) {\n      display.clearDisplay();\n      display.setCursor(20, 5);\n      display.println( roll);\n      display.setCursor(20, 25);\n      display.println( Duty);\n      display.setCursor(20, 45);\n      display.println( power);\n      display.display();\n    }\n  } else {                                                  \/\/ \u8ee2\u5012\u3057\u305f\u3089\u505c\u6b62\n    ledcWrite(MOTOR_PWM_F, 0);\n    ledcWrite(MOTOR_PWM_R, 0);\n    power = 0;\n    I = 0;\n    digitalWrite(LED_PIN, LOW);\n  }\n\n}\n\n\/\/**************************************************************\nvoid LED_PWM(byte Led_gr, byte channel, int data_i) {\n  Serial.println(data_i);\n}\n\/\/*********************************************\nvoid websocket_send(uint8_t count, String str_txt) {\n  String str, tmp;\n  \/\/\u203bWebSocket\u3078\u306e\u30c6\u30ad\u30b9\u30c8\u9001\u4fe1\u306f110 byte \u7a0b\u5ea6\u306a\u306e\u3067\u3001\u5168\u89d2\uff13\uff15\u6587\u5b57\u7a0b\u5ea6\u306b\u6291\u3048\u308b\u3053\u3068\n  tmp = &quot;AGL=&quot; + String(roll) + &quot;,TGT=&quot; + String(TARGET) + &quot;,P=&quot; + String(KP) +  &quot;,I=&quot; + String(KI) + &quot;,D=&quot; + String(KD);\n  switch (cnt) {\n    case 0:\n      \/\/str = str_txt;\n      str = tmp;\n      break;\n    case 1:\n      str = tmp;\n      break;\n    case 2:\n      str = tmp;\n      break;\n    case 3:\n      str = tmp;\n      break;\n  }\n\n  ews.EWS_ESP32_Str_SEND(str, &quot;wroomTXT&quot;); \/\/\u30d6\u30e9\u30a6\u30b6\u306b\u6587\u5b57\u5217\u3092\u9001\u4fe1\n}\n\/\/************************* Websocket handshake **************************************\nvoid websocket_handshake() {\n  if (ews.Get_Http_Req_Status()) { \/\/\u30d6\u30e9\u30a6\u30b6\u304b\u3089GET\u30ea\u30af\u30a8\u30b9\u30c8\u304c\u3042\u3063\u305f\u304b\u3069\u3046\u304b\u306e\u5224\u5b9a\n    String html_str1 = &quot;&quot;, html_str2 = &quot;&quot;, html_str3 = &quot;&quot;, html_str4 = &quot;&quot;, html_str5 = &quot;&quot;, html_str6 = &quot;&quot;, html_str7 = &quot;&quot;;\n\n    \/\/\u203bString\u5909\u6570\u4e00\u3064\u306bEWS_Canvas_Slider_T\u95a2\u6570\u306f\uff12\u3064\u307e\u3067\u3057\u304b\u5165\u3089\u306a\u3044\n    html_str1 += &quot;&lt;body style=&#39;background:#000; color:#fff;&#39;&gt;\\r\\n&quot;;\n    html_str1 += &quot;&lt;font size=3&gt;\\r\\n&quot;;\n    html_str1 += &quot;ESP-WROOM-32(ESP32)\\r\\n&quot;;\n    html_str1 += &quot;&lt;br&gt;\\r\\n&quot;;\n    html_str1 += &quot;ESP32_SPIFFS_EasyWebSocket Beta1.60 Sample\\r\\n&quot;;\n    html_str1 += &quot;&lt;\/font&gt;&lt;br&gt;\\r\\n&quot;;\n    html_str1 += ews.EWS_BrowserSendRate();\n    html_str1 += &quot;&lt;br&gt;\\r\\n&quot;;\n    html_str1 += ews.EWS_ESP32_SendRate(&quot;!esp32t-Rate&quot;);\n    html_str1 += &quot;&lt;br&gt;\\r\\n&quot;;\n    html_str1 += ews.EWS_BrowserReceiveTextTag2(&quot;wroomTXT&quot;, &quot;from ESP32 DATA&quot;, &quot;#555&quot;, 20, &quot;#00FF00&quot;);\n    html_str1 += &quot;&lt;br&gt;\\r\\n&quot;;\n    html_str1 += ews.EWS_Status_Text2(&quot;WebSocket Status&quot;, &quot;#555&quot;, 20, &quot;#FF00FF&quot;);\n    html_str1 += &quot;&lt;br&gt;&lt;br&gt;\\r\\n&quot;;\n\n    html_str2 += ews.EWS_TextBox_Send(&quot;txt1&quot;, &quot;Hello Easy WebSocket Beta1.60&quot;, &quot;\u9001\u4fe1&quot;);\n    html_str2 += &quot;&lt;br&gt;&lt;br&gt;\\r\\n&quot;;\n    html_str2 += &quot;SETTING \\r\\n&quot;;\n    html_str2 += ews.EWS_On_Momentary_Button(&quot;ALL&quot;, &quot;ALL-ON&quot;, 80, 25, 15, &quot;#000000&quot;, &quot;#AAAAAA&quot;);\n    html_str2 += ews.EWS_On_Momentary_Button(&quot;OUT&quot;, &quot;DEFALT&quot;, 80, 25, 15, &quot;#FFFFFF&quot;, &quot;#555555&quot;);\n    html_str2 += &quot;&lt;br&gt;\\r\\n&quot;;\n\n    html_str3 += &quot;&lt;br&gt;TGT_ :\\r\\n&quot;;\n    html_str3 += ews.EWS_Canvas_Slider_T(&quot;BLUE&quot;, 240, 40, &quot;#777777&quot;, &quot;#0000ff&quot;); \/\/Canvas\u30b9\u30e9\u30a4\u30c0\u30fc\u306fString\u6587\u5b57\u5217\u306b\uff12\u3064\u307e\u3067\u3057\u304b\u5165\u3089\u306a\u3044\n    html_str3 += &quot;&lt;br&gt;PID P:\\r\\n&quot;;\n    html_str3 += ews.EWS_Canvas_Slider_T(&quot;GREEN&quot;, 250, 40, &quot;#777777&quot;, &quot;#00ff00&quot;); \/\/Canvas\u30b9\u30e9\u30a4\u30c0\u30fc\u306fString\u6587\u5b57\u5217\u306b\uff12\u3064\u307e\u3067\u3057\u304b\u5165\u3089\u306a\u3044\n\n    html_str4 += &quot;&lt;br&gt;PID I:\\r\\n&quot;;\n    html_str4 += ews.EWS_Canvas_Slider_T(&quot;RED&quot;, 250, 40, &quot;#777777&quot;, &quot;#ff0000&quot;); \/\/Canvas\u30b9\u30e9\u30a4\u30c0\u30fc\u306fString\u6587\u5b57\u5217\u306b\uff12\u3064\u307e\u3067\u3057\u304b\u5165\u3089\u306a\u3044\n    html_str4 += &quot;&lt;br&gt;PID D:\\r\\n&quot;;\n    html_str4 += ews.EWS_Canvas_Slider_T(&quot;_RGB&quot;, 250, 40, &quot;#777777&quot;, &quot;#ffff00&quot;);\n\n    html_str7 += &quot;&lt;br&gt;&lt;br&gt;\\r\\n&quot;;\n    html_str7 += ews.EWS_WebSocket_Reconnection_Button2(&quot;WS-Reconnect&quot;, &quot;grey&quot;, 200, 40, &quot;black&quot; , 17);\n    html_str7 += &quot;&lt;br&gt;&lt;br&gt;\\r\\n&quot;;\n    html_str7 += ews.EWS_Close_Button2(&quot;WS CLOSE&quot;, &quot;#bbb&quot;, 150, 40, &quot;red&quot;, 17);\n    html_str7 += ews.EWS_Window_ReLoad_Button2(&quot;ReLoad&quot;, &quot;#bbb&quot;, 150, 40, &quot;blue&quot;, 17);\n    html_str7 += &quot;&lt;\/body&gt;&lt;\/html&gt;&quot;;\n\n    \/\/WebSocket \u30cf\u30f3\u30c9\u30b7\u30a7\u30a4\u30af\u95a2\u6570\n    ews.EWS_HandShake_main(3, HTM_head_file1, HTM_head_file2, HTML_body_file, dummy_file, LIP, html_str1, html_str2, html_str3, html_str4, html_str5, html_str6, html_str7);\n  }\n}<\/code><\/pre><\/div>\n","protected":false},"excerpt":{"rendered":"<p>PID\u5236\u5fa1\u306e\u30d1\u30e9\u30e1\u30fc\u30bf\u3068\u81ea\u7acb\u306e\u305f\u3081\u306e\u76ee\u6a19\u89d2\u5ea6\uff08TARGET)\u3092Websocket UI\u3067\u30b9\u30de\u30db\u304b\u3089\u8a2d\u5b9a\u3057\u307e\u3059\u3002\u4eca\u306e\u3068\u3053\u308d\u3001\u30d1\u30e9\u30e1\u30fc\u30bf\u306e\u5024\u304c\u9069\u5207\u3067\u306a\u3044\u3088\u3046\u3067\u3001\u786c\u3044\u5e8a\u9762\u4e0a\u3067\u306f\u77ed\u6642\u9593\u3067\u5012\u308c\u307e\u3059\u3002\u3084\u308f\u3089\u304b\u3044\u7d20\u6750\u306e\u4e0a\u3067\u306f\u5012\u308c\u306a\u3044\u306e [&hellip;]<\/p>\n","protected":false},"author":1,"featured_media":0,"comment_status":"open","ping_status":"open","sticky":false,"template":"","format":"standard","meta":{"_jetpack_memberships_contains_paid_content":false,"footnotes":""},"categories":[6],"tags":[],"class_list":["post-216","post","type-post","status-publish","format-standard","hentry","category-make"],"featured_image_src":null,"author_info":{"display_name":"mars","author_link":"https:\/\/rfsec.ddns.net\/db\/?author=1"},"jetpack_featured_media_url":"","jetpack_sharing_enabled":true,"_links":{"self":[{"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=\/wp\/v2\/posts\/216","targetHints":{"allow":["GET"]}}],"collection":[{"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=\/wp\/v2\/posts"}],"about":[{"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=\/wp\/v2\/types\/post"}],"author":[{"embeddable":true,"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=\/wp\/v2\/users\/1"}],"replies":[{"embeddable":true,"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=%2Fwp%2Fv2%2Fcomments&post=216"}],"version-history":[{"count":2,"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=\/wp\/v2\/posts\/216\/revisions"}],"predecessor-version":[{"id":218,"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=\/wp\/v2\/posts\/216\/revisions\/218"}],"wp:attachment":[{"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=%2Fwp%2Fv2%2Fmedia&parent=216"}],"wp:term":[{"taxonomy":"category","embeddable":true,"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=%2Fwp%2Fv2%2Fcategories&post=216"},{"taxonomy":"post_tag","embeddable":true,"href":"https:\/\/rfsec.ddns.net\/db\/index.php?rest_route=%2Fwp%2Fv2%2Ftags&post=216"}],"curies":[{"name":"wp","href":"https:\/\/api.w.org\/{rel}","templated":true}]}}