# Microros micro-ROS คือเวอร์ชันย่อของ ROS 2 (Robot Operating System 2) ออกแบบมาสำหรับ “ไมโครคอนโทรลเลอร์” เช่น ESP32, STM32, Arduino, Teensy, ฯลฯ ที่มีทรัพยากรจำกัด\ บทนี้จะสอนการติดตั้งและ build micro-ROS Agent ผ่าน ซึ่งเป็นตัวกลาง (Bridge) เชื่อมการสื่อสารระหว่าง ROS 2 ที่อยู่บน PC ↔ microcontroller (เช่น ESP32) ที่รัน micro-ROS firmware โดยเราจะติดตั้ง Arduino IDE 2.0 ไว้ใน Windows/Mac host machine ที่ลิ้งค์ https://www.arduino.cc/en/software/ และใน Boards Manager ให้ติดตั้ง esp32 by Espressif Systems version 3.X. ดูวิธีการทำได้จาก https://randomnerdtutorials.com/installing-esp32-arduino-ide-2-0/ และ Add .zip library ใน Arduino IDE จากลิ้งค์ https://github.com/micro-ROS/micro_ros_arduino/releases โดยเลือกเวอร์ชั่น v2.0.8-Jazzy (Source code .zip) ## ขั้นตอนการติดตั้งผ่าน setup_microros.sh และขั้นตอนการเชื่อมต่อบน Ubuntu 1) เปิด Terminal และใช้คำสั่งสร้างไฟล์ setup_microros.sh ไว้ตำแหน่งหน้า Home ```{code-block} bash gedit setup_microros.sh ``` 2) copy เนื้อหาใส่ setup_microros.sh ดังนี้ ```{code-block} bash #!/bin/bash # setup_microros.sh install and build micro-ROS agent workspace set -euo pipefail # ---------- install git (added) ---------- echo "Installing git..." sudo apt update sudo apt install -y git # ---------- helper: retry mechanism ---------- retry() { local max=3 delay=10 n=1 while true; do eval "$@" status=$? if [[ $status -eq 0 ]]; then return 0 fi if [[ $n -lt $max ]]; then echo "Attempt $n/$max failed (exit $status). Retrying in ${delay}s: $*" sleep "$delay" n=$((n+1)) else echo "Command failed after $max attempts: $*" return $status fi done } # ---------- permissions ---------- echo "Adding $USER to dialout (for serial/USB)..." sudo usermod -a -G dialout "$USER" || true # ---------- workspace ---------- cd ~ mkdir -p microros_ws/src cd ~/microros_ws # Detect ROS distro if not set if [[ -z "${ROS_DISTRO:-}" ]]; then if [[ -d /opt/ros ]]; then ROS_DISTRO="$(ls /opt/ros | head -n1)" echo "ROS_DISTRO not set. Using detected: $ROS_DISTRO" else echo "ROS2 not found. Please install ROS2 and/or export ROS_DISTRO before running." exit 1 fi fi # ---------- clone micro-ROS setup ---------- if [[ ! -d src/micro_ros_setup ]]; then git clone -b "$ROS_DISTRO" https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup fi # ---------- dependencies ---------- sudo apt update sudo rosdep init 2>/dev/null || true rosdep update rosdep install --from-paths src --ignore-src -y sudo apt-get install -y python3-pip # ---------- build & source safely ---------- colcon build if [ -f install/local_setup.bash ]; then set +u source install/local_setup.bash set -u fi # ---------- build micro-ROS agent ---------- retry "ros2 run micro_ros_setup create_agent_ws.sh" retry "ros2 run micro_ros_setup build_agent.sh" if [ -f install/local_setup.bash ]; then set +u source install/local_setup.bash set -u fi # ---------- persist sourcing ---------- if ! grep -Fxq "source ~/microros_ws/install/local_setup.bash" ~/.bashrc; then echo "source ~/microros_ws/install/local_setup.bash" >> ~/.bashrc echo "Added workspace sourcing to ~/.bashrc" else echo "Workspace sourcing already in ~/.bashrc" fi echo echo "micro-ROS agent setup complete." echo "Log out or reboot for 'dialout' group membership to take effect." ``` 3) ใช้คำสั่งเพื่อเปิดสิทธิ์การเข้าถึงไฟล์ ```{code-block} bash chmod +x setup_microros.sh ``` 4) รันสคริปต์เพื่อติดตั้ง ```{code-block} bash ./setup_microros.sh ``` 5) รีบูท Ubuntu ```{code-block} bash sudo reboot ``` 6) กำหนดสิทธิ์ให้กับพอต ```{code-block} bash sudo chmod 666 /dev/ttyUSB0 ``` 7) เปิดไฟล์ .bashrc และใส่ # ไว้ข้างหน้า export ROS_DOMAIN_ID=30 ```{code-block} bash gedit ~/.bashrc ``` 8) source ~/.bashrc ทุกหน้าต่าง หรือเปิด terminal แล้วเปิดใหม่ 9) ต่อ ESP32 ที่อัพโค้ด micro ros แล้วเข้า vm 10) รัน dmesg | grep tty เพื่อดู port ของ ESP32 (มักจะได้ชื่ออุปกรณ์เป็น /dev/ttyUSB0 หรือ /dev/ttyACM0) ```{code-block} bash sudo dmesg | grep tty ``` 11) รัน micro-ROS Agent เพื่อต่อกับ ESP32 ```{code-block} bash ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 ``` 12) กดปุ่ม BOOT บนบอร์ด ESP32 13) สังเกตข้อความการเชื่อมต่อ ที่หน้าต่างของ Agent จะขึ้น log การเชื่อมต่อ ดังภาพตัวอย่าง ```{image} images/c17/17.1.png :width: 80% :align: center ``` ## ตัวอย่างโค้ด micro-ROS ### Control LED ```{code-block} cpp // ESP32 with micROS : Control LED via ROS2 Topics (Improved Version) #include #include #include #include #include #include #include #include #define LED_PIN 4 // LED Pin (connected to R 220Ω then to GND) #define LED_BUILTIN 13 // Built-in LED for some ESP32 boards #define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}} #define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}} rcl_subscription_t subscriber_led; rcl_publisher_t publisher_status; std_msgs__msg__Bool led_msg; std_msgs__msg__String status_msg; rclc_executor_t executor; rclc_support_t support; rcl_allocator_t allocator; rcl_node_t node; void error_loop(){ while(1){ digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); delay(100); } } // Callback for receiving Bool commands (true/false) void led_callback(const void * msgin) { const std_msgs__msg__Bool * msg = (const std_msgs__msg__Bool *)msgin; bool led_state = msg->data; digitalWrite(LED_PIN, led_state ? HIGH : LOW); // Prepare and publish the status update sprintf(status_msg.data.data, led_state ? "LED is ON" : "LED is OFF"); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); } void setup() { Serial.begin(115200); // Set up WiFi transport for micro-ROS set_microros_transports(); pinMode(LED_PIN, OUTPUT); pinMode(LED_BUILTIN, OUTPUT); delay(2000); allocator = rcl_get_default_allocator(); // Create init_options RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); // Create node RCCHECK(rclc_node_init_default(&node, "esp32_led_controller", "", &support)); // Create subscriber for Bool messages RCCHECK(rclc_subscription_init_default( &subscriber_led, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool), "led_control")); // Create publisher for status messages RCCHECK(rclc_publisher_init_default( &publisher_status, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "led_status")); // Prepare status message buffer status_msg.data.data = (char*) malloc(100 * sizeof(char)); status_msg.data.size = 0; status_msg.data.capacity = 100; // Create executor with 1 subscription RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber_led, &led_msg, &led_callback, ON_NEW_DATA)); // Send an initial status message sprintf(status_msg.data.data, "ESP32 LED Controller is ready."); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); } void loop() { // REMOVED the delay(100). // The executor's spin function handles the necessary waiting and message checking. // This makes the node much more responsive. RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100))); } ``` ### Control LED with Potentiometer + ROS2 Commands ```{code-block} cpp // ESP32 with micROS : Control LED with Potentiometer + ROS2 Commands #include #include #include #include #include #include #include #include #include #include #define LED_PIN 4 // ขา LED (ผ่าน R 220Ω ลง GND) #define POT_PIN 34 // ขา Analog Input (กลางของ Pot) #define LED_BUILTIN 13 // LED builtin สำหรับ ZY-ESP32 #define PUBLISH_FREQUENCY 5 // ส่งข้อมูลทุก 5 Hz (200ms) #define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}} #define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}} // ROS objects rcl_subscription_t subscriber_command; // รับคำสั่ง String เท่านั้น (on/off/auto/manual/brightness:xxx) rcl_publisher_t publisher_pot_raw; // ส่งค่า Potentiometer ดิบ rcl_publisher_t publisher_pot_percent; // ส่งค่า Potentiometer เป็น % rcl_publisher_t publisher_brightness; // ส่งค่าความสว่างที่ใช้จริง rcl_publisher_t publisher_led_state; // ส่งสถานะ LED (เปิด/ปิด) rcl_publisher_t publisher_status; // ส่งข้อความสถานะ rcl_timer_t timer; std_msgs__msg__String command_msg; std_msgs__msg__Int32 pot_raw_msg; std_msgs__msg__Float32 pot_percent_msg; std_msgs__msg__Int32 brightness_out_msg; std_msgs__msg__Bool led_state_msg; std_msgs__msg__String status_msg; rclc_executor_t executor; rclc_support_t support; rcl_allocator_t allocator; rcl_node_t node; // Control variables bool led_enabled = true; // สถานะเปิด/ปิด LED bool auto_mode = true; // โหมดอัตโนมัติ (ใช้ Potentiometer) int manual_brightness = 128; // ความสว่างแบบ manual (0-255) int current_brightness = 0; // ความสว่างปัจจุบัน void error_loop(){ unsigned long lastToggle = 0; while(1){ // ใช้ millis() แทน delay() เพื่อไม่ block execution if (millis() - lastToggle >= 100) { digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); lastToggle = millis(); } } } // Callback สำหรับรับคำสั่ง String (รองรับหลายคำสั่ง) void command_callback(const void * msgin) { const std_msgs__msg__String * msg = (const std_msgs__msg__String *)msgin; // คำสั่ง on/off if (strcmp(msg->data.data, "on") == 0) { led_enabled = true; sprintf(status_msg.data.data, "💡 LED เปิด"); } else if (strcmp(msg->data.data, "off") == 0) { led_enabled = false; sprintf(status_msg.data.data, "💤 LED ปิด"); } // คำสั่ง auto/manual mode else if (strcmp(msg->data.data, "auto") == 0) { auto_mode = true; sprintf(status_msg.data.data, "🤖 โหมดอัตโนมัติ (ใช้ Potentiometer)"); } else if (strcmp(msg->data.data, "manual") == 0) { auto_mode = false; sprintf(status_msg.data.data, "👤 โหมดควบคุมด้วยมือ"); } // คำสั่งตั้งค่าความสว่าง: brightness:xxx (เช่น brightness:128) else if (strncmp(msg->data.data, "brightness:", 11) == 0) { int value = atoi(msg->data.data + 11); // ดึงตัวเลขหลัง "brightness:" manual_brightness = constrain(value, 0, 255); auto_mode = false; // เปลี่ยนเป็นโหมด manual sprintf(status_msg.data.data, "🔆 Manual Brightness: %d", manual_brightness); } else { sprintf(status_msg.data.data, "⚠️ คำสั่งไม่ถูกต้อง (on/off/auto/manual/brightness:xxx)"); } status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); } // Timer callback - อ่านและควบคุม LED void timer_callback(rcl_timer_t * timer, int64_t last_call_time) { RCLC_UNUSED(last_call_time); if (timer != NULL) { // อ่านค่าจาก Potentiometer int pot_value = analogRead(POT_PIN); float pot_percent = (pot_value / 4095.0) * 100.0; // คำนวณความสว่าง int target_brightness = 0; if (led_enabled) { if (auto_mode) { target_brightness = map(pot_value, 0, 4095, 0, 255); } else { target_brightness = manual_brightness; } } current_brightness = target_brightness; // ควบคุม LED analogWrite(LED_PIN, current_brightness); // ส่งข้อมูลผ่าน ROS topics // ส่งค่า Potentiometer pot_raw_msg.data = pot_value; RCSOFTCHECK(rcl_publish(&publisher_pot_raw, &pot_raw_msg, NULL)); pot_percent_msg.data = pot_percent; RCSOFTCHECK(rcl_publish(&publisher_pot_percent, &pot_percent_msg, NULL)); // ส่งค่าความสว่าง brightness_out_msg.data = current_brightness; RCSOFTCHECK(rcl_publish(&publisher_brightness, &brightness_out_msg, NULL)); // ส่งสถานะ LED led_state_msg.data = led_enabled; RCSOFTCHECK(rcl_publish(&publisher_led_state, &led_state_msg, NULL)); // ส่งข้อความสถานะรายละเอียด (ทุก 1 วินาที) static int status_counter = 0; if (++status_counter >= PUBLISH_FREQUENCY) { sprintf(status_msg.data.data, "🎛️ Pot:%d(%.1f%%) | 💡:%s | 🔆:%d | Mode:%s", pot_value, pot_percent, led_enabled ? "ON" : "OFF", current_brightness, auto_mode ? "AUTO" : "MANUAL"); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); status_counter = 0; } } } void setup() { Serial.begin(115200); // ตั้งค่า WiFi transport สำหรับ micROS set_microros_transports(); pinMode(LED_PIN, OUTPUT); pinMode(LED_BUILTIN, OUTPUT); delay(2000); allocator = rcl_get_default_allocator(); // สร้าง init_options RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); // สร้าง node RCCHECK(rclc_node_init_default(&node, "esp32_led_potentiometer", "", &support)); // สร้าง subscriber เพียง 1 topic RCCHECK(rclc_subscription_init_default( &subscriber_command, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "led/command")); // สร้าง publishers RCCHECK(rclc_publisher_init_default( &publisher_pot_raw, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "potentiometer/raw")); RCCHECK(rclc_publisher_init_default( &publisher_pot_percent, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32), "potentiometer/percent")); RCCHECK(rclc_publisher_init_default( &publisher_brightness, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "led/brightness_actual")); RCCHECK(rclc_publisher_init_default( &publisher_led_state, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool), "led/state")); RCCHECK(rclc_publisher_init_default( &publisher_status, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "led/status")); // สร้าง timer const unsigned int timer_timeout = 1000 / PUBLISH_FREQUENCY; RCCHECK(rclc_timer_init_default( &timer, &support, RCL_MS_TO_NS(timer_timeout), timer_callback)); // เตรียม message buffers command_msg.data.data = (char*) malloc(50 * sizeof(char)); command_msg.data.size = 0; command_msg.data.capacity = 50; status_msg.data.data = (char*) malloc(150 * sizeof(char)); status_msg.data.size = 0; status_msg.data.capacity = 150; // สร้าง executor (1 subscription + 1 timer = 2) RCCHECK(rclc_executor_init(&executor, &support.context, 2, &allocator)); RCCHECK(rclc_executor_add_subscription(&executor, &subscriber_command, &command_msg, &command_callback, ON_NEW_DATA)); RCCHECK(rclc_executor_add_timer(&executor, &timer)); // ส่งข้อความเริ่มต้น sprintf(status_msg.data.data, "🤖 ESP32 LED+Potentiometer Controller พร้อมใช้งาน"); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); Serial.println("=== micROS LED+Potentiometer Controller ==="); Serial.println("🎛️ โหมดอัตโนมัติ: ใช้ Potentiometer ควบคุม"); } void loop() { // ไม่ใส่ delay() เพราะ spin_some จัดการ timing เองอยู่แล้ว RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100))); } ``` ### Read Potentiometer and Publish to ROS2 Topics ```{code-block} cpp // ESP32 with micROS : Read Potentiometer and Publish to ROS2 Topics #include #include #include #include #include #include #include #include #include #define POT_PIN 34 // ขา ADC (Analog Input) — ต่อกลางของ Pot #define LED_BUILTIN 13 // LED builtin สำหรับ ZY-ESP32 #define PUBLISH_FREQUENCY 5 // ส่งข้อมูลทุก 5 Hz (200ms) #define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}} #define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}} // ROS objects rcl_publisher_t publisher_raw; // ส่งค่าดิบ (0-4095) rcl_publisher_t publisher_voltage; // ส่งค่าแรงดัน (0-3.3V) rcl_publisher_t publisher_percent; // ส่งค่าเปอร์เซ็นต์ (0-100%) rcl_publisher_t publisher_status; // ส่งข้อความสถานะ rcl_timer_t timer; std_msgs__msg__Int32 raw_msg; std_msgs__msg__Float32 voltage_msg; std_msgs__msg__Float32 percent_msg; std_msgs__msg__String status_msg; rclc_executor_t executor; rclc_support_t support; rcl_allocator_t allocator; rcl_node_t node; int last_pot_value = -1; void error_loop(){ while(1){ digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); delay(100); } } // Timer callback - อ่านและส่งค่า Potentiometer void timer_callback(rcl_timer_t * timer, int64_t last_call_time) { RCLC_UNUSED(last_call_time); if (timer != NULL) { // อ่านค่าจาก Potentiometer int pot_value = analogRead(POT_PIN); // คำนวณค่าต่างๆ float voltage = (pot_value / 4095.0) * 3.3; // แปลงเป็นแรงดัน (0-3.3V) float percent = (pot_value / 4095.0) * 100.0; // แปลงเป็นเปอร์เซ็นต์ (0-100%) // ส่งค่าดิบ (Raw ADC Value) raw_msg.data = pot_value; RCSOFTCHECK(rcl_publish(&publisher_raw, &raw_msg, NULL)); // ส่งค่าแรงดัน voltage_msg.data = voltage; RCSOFTCHECK(rcl_publish(&publisher_voltage, &voltage_msg, NULL)); // ส่งค่าเปอร์เซ็นต์ percent_msg.data = percent; RCSOFTCHECK(rcl_publish(&publisher_percent, &percent_msg, NULL)); // ส่งข้อความสถานะ (เฉพาะเมื่อค่าเปลี่ยน) if (abs(pot_value - last_pot_value) > 10) { // ป้องกันการส่งบ่อยเกินไป sprintf(status_msg.data.data, "Pot: %d | %.2fV | %.1f%%", pot_value, voltage, percent); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); last_pot_value = pot_value; } } } void setup() { Serial.begin(115200); // ตั้งค่า WiFi transport สำหรับ micROS set_microros_transports(); pinMode(LED_BUILTIN, OUTPUT); delay(2000); allocator = rcl_get_default_allocator(); // สร้าง init_options RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); // สร้าง node RCCHECK(rclc_node_init_default(&node, "esp32_potentiometer", "", &support)); // สร้าง publishers RCCHECK(rclc_publisher_init_default( &publisher_raw, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "potentiometer/raw")); RCCHECK(rclc_publisher_init_default( &publisher_voltage, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32), "potentiometer/voltage")); RCCHECK(rclc_publisher_init_default( &publisher_percent, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32), "potentiometer/percent")); RCCHECK(rclc_publisher_init_default( &publisher_status, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "potentiometer/status")); // สร้าง timer สำหรับส่งข้อมูลเป็นระยะ const unsigned int timer_timeout = 1000 / PUBLISH_FREQUENCY; // milliseconds RCCHECK(rclc_timer_init_default( &timer, &support, RCL_MS_TO_NS(timer_timeout), timer_callback)); // เตรียม message buffer status_msg.data.data = (char*) malloc(100 * sizeof(char)); status_msg.data.size = 0; status_msg.data.capacity = 100; // สร้าง executor RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); RCCHECK(rclc_executor_add_timer(&executor, &timer)); // ส่งข้อความเริ่มต้น sprintf(status_msg.data.data, "ESP32 Potentiometer Reader พร้อมใช้งาน"); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); Serial.println("🎛️ micROS Potentiometer Reader เริ่มทำงาน"); } void loop() { // ไม่ใส่ delay() เพราะ spin_some จัดการ timing เองอยู่แล้ว RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100))); } ``` ### Read Push Button and Publish to ROS2 Topics ```{code-block} cpp // ESP32 with micROS : Read Push Button and Publish to ROS2 Topics #include #include #include #include #include #include #include #include #include #define BTN_PIN 27 // ขาปุ่มกด (ต่อกับ GND) #define LED_BUILTIN 13 // LED builtin สำหรับ ZY-ESP32 #define PUBLISH_FREQUENCY 10 // ตรวจสอบทุก 100ms #define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}} #define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}} // ROS objects rcl_publisher_t publisher_state; // ส่งสถานะปุ่ม (true/false) rcl_publisher_t publisher_pressed; // ส่ง event เมื่อกดปุ่ม rcl_publisher_t publisher_released; // ส่ง event เมื่อปล่อยปุ่ม rcl_publisher_t publisher_count; // ส่งจำนวนครั้งที่กด rcl_publisher_t publisher_status; // ส่งข้อความสถานะ rcl_timer_t timer; std_msgs__msg__Bool state_msg; std_msgs__msg__Bool pressed_msg; std_msgs__msg__Bool released_msg; std_msgs__msg__Int32 count_msg; std_msgs__msg__String status_msg; rclc_executor_t executor; rclc_support_t support; rcl_allocator_t allocator; rcl_node_t node; // ตัวแปรสำหรับ debouncing และ event detection bool current_state = HIGH; // สถานะปัจจุบัน bool last_state = HIGH; // สถานะครั้งก่อน bool last_stable_state = HIGH; // สถานะที่เสถียร unsigned long last_debounce_time = 0; unsigned long debounce_delay = 50; // 50ms debounce int press_count = 0; void error_loop(){ while(1){ digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); delay(100); } } // Timer callback - ตรวจสอบและส่งสถานะปุ่ม void timer_callback(rcl_timer_t * timer, int64_t last_call_time) { RCLC_UNUSED(last_call_time); if (timer != NULL) { // อ่านสถานะปุ่มกด bool reading = digitalRead(BTN_PIN); // Debouncing logic if (reading != last_state) { last_debounce_time = millis(); } if ((millis() - last_debounce_time) > debounce_delay) { // สถานะเปลี่ยนแปลงแล้วเสถียร if (reading != current_state) { current_state = reading; // ส่งสถานะปัจจุบัน (inverted เพราะใช้ pull-up) state_msg.data = !current_state; // กด = true, ปล่อย = false RCSOFTCHECK(rcl_publish(&publisher_state, &state_msg, NULL)); // ตรวจสอบ events if (current_state == LOW) { // ปุ่มถูกกด (LOW เพราะใช้ pull-up) // Button pressed event pressed_msg.data = true; RCSOFTCHECK(rcl_publish(&publisher_pressed, &pressed_msg, NULL)); // เพิ่มจำนวนครั้งที่กด press_count++; count_msg.data = press_count; RCSOFTCHECK(rcl_publish(&publisher_count, &count_msg, NULL)); // ส่งข้อความสถานะ sprintf(status_msg.data.data, "🔘 ปุ่มถูกกด! ครั้งที่ %d", press_count); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); // เปิด LED builtin เมื่อกดปุ่ม digitalWrite(LED_BUILTIN, HIGH); } else { // ปุ่มถูกปล่อย (HIGH เพราะใช้ pull-up) // Button released event released_msg.data = true; RCSOFTCHECK(rcl_publish(&publisher_released, &released_msg, NULL)); // ส่งข้อความสถานะ sprintf(status_msg.data.data, "🔘 ปุ่มถูกปล่อย"); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); // ปิด LED builtin เมื่อปล่อยปุ่ม digitalWrite(LED_BUILTIN, LOW); } } } last_state = reading; } } void setup() { Serial.begin(115200); // ตั้งค่า WiFi transport สำหรับ micROS set_microros_transports(); pinMode(BTN_PIN, INPUT_PULLUP); // ใช้ internal pull-up resistor pinMode(LED_BUILTIN, OUTPUT); digitalWrite(LED_BUILTIN, LOW); delay(2000); allocator = rcl_get_default_allocator(); // สร้าง init_options RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); // สร้าง node RCCHECK(rclc_node_init_default(&node, "esp32_button_reader", "", &support)); // สร้าง publishers RCCHECK(rclc_publisher_init_default( &publisher_state, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool), "button/state")); RCCHECK(rclc_publisher_init_default( &publisher_pressed, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool), "button/pressed")); RCCHECK(rclc_publisher_init_default( &publisher_released, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool), "button/released")); RCCHECK(rclc_publisher_init_default( &publisher_count, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "button/press_count")); RCCHECK(rclc_publisher_init_default( &publisher_status, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), "button/status")); // สร้าง timer สำหรับตรวจสอบปุ่ม const unsigned int timer_timeout = 1000 / PUBLISH_FREQUENCY; // milliseconds RCCHECK(rclc_timer_init_default( &timer, &support, RCL_MS_TO_NS(timer_timeout), timer_callback)); // เตรียม message buffer status_msg.data.data = (char*) malloc(100 * sizeof(char)); status_msg.data.size = 0; status_msg.data.capacity = 100; // สร้าง executor RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); RCCHECK(rclc_executor_add_timer(&executor, &timer)); // ส่งข้อความเริ่มต้น sprintf(status_msg.data.data, "🤖 ESP32 Button Reader พร้อมใช้งาน"); status_msg.data.size = strlen(status_msg.data.data); RCSOFTCHECK(rcl_publish(&publisher_status, &status_msg, NULL)); Serial.println("🔘 micROS Button Reader เริ่มทำงาน"); Serial.println("กด = true, ปล่อย = false"); } void loop() { // ไม่ใส่ delay() เพราะ spin_some จัดการ timing เองอยู่แล้ว RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100))); } ```