คู่มือการใช้งานบอร์ด C6 Kits
บอร์ดการเรียนรู้ C6 Kits ใช้ไมโครคอนโทรลเลอร์ ESP32 C6 สามารถเชื่อมต่อ WiFi และ Bluetooth เหมาะสำหรับทำโครงงาน IoT หรือหุ่นยนต์ขนาดเล็กด้วยบอร์ดมีขนาดเพียง 60×70 มิลลิเมตร และสามารถขับมอเตอร์ DC ได้ถึง 2 ตัว มีช่องต่อเซ็นเซอร์ทั้งหมด 6 ช่อง ในกรณีที่ใช้งานเซอร์โวมอเตอร์สามารถต่อได้ 6 ตัว แต่ไม่สามารถต่อใช้เซ็นเซอร์และเซอร์โวพร้อมกันบน GPIO เดียวกันได้เนื่องจากใช้ GPIO ร่วมกัน มีช่องต่อ I2C แบบ JST XH2.54 สำหรับต่อบอร์ดเสริมหรือเซ็นเซอร์ประเภท I2C และ pin header I2C สำหรับต่อจอ OLED ขนาด 0.96″ ใช้ไฟเลี้ยงวงจร 7-10 โวลต์ หรือเท่ากับแบตเตอรี่ลิเธี่ยม 2 เซลล์ มีไดโอดป้องกันการต่อกลับขั้ว
ส่วนประกอบบนบอร์ด C6 Kits
- ช่องต่อไฟเลี้ยงบอร์ด ใช้ไฟกระแสตรงแรงดัน 7-10V.
- สวิตซ์เปิด-ปิดการทำงาน
- หลอดไฟแสดงสถานะ
- ช่องต่อ I2C สำหรับต่อเซ็นเซอร์หรือบอร์ดเสริม แบบ JST XH2.54
– SDA = GPIO16
– SCL = GPIO17 - ช่องต่อ I2C สำหรับต่อจอ OLED 0.96″ หรือเซ็นเซอร์ I2C ที่ใช้หัวแบบ Dupont
- ช่องต่อเซ็นเซอร์แบบ JST PH2.0 จำนวน 6 ช่องได้แก่ GPIO01, GPIO2, GPIO3, GPIO4, GPIO5, GPIO6 เรียงลำดับตามที่ระบุไว้ข้างคอนเนคเตอร์
- Rotary Encoder ตรวจจับทิศทางการหมุนและกดปุ่ม
– CLK = GPIO18
– DT = GPIO19
– SW = GPIO20 - Pin header สำหรับต่อเซอร์โวมอเตอร์จำนวน 6 ช่องได้แก่ GPIO01, GPIO2, GPIO3, GPIO4, GPIO5, GPIO6 เรียงลำดับตามที่ระบุไว้ข้าง Pin header ข้อควรระวังจุดนี้จ่ายไฟเลี้ยง 5V จะใช้งานได้เมื่อต่อไฟเลี้ยงบอร์ดที่ช่องหมายเลข 1 เท่านั้น
- ESP32 C6 เป็นหน่วยประมวลผลของบอร์ดนี้ใช้สาย USB Type-C ในการเชื่อมต่อ ไฟเลี้ยง 5V จากสาย USB จะไม่ถูกส่งต่อไปยังไฟเลี้ยง 5V ของเซอร์โวมอเตอร์เพื่อป้องกันความเสียหาย บนบอร์ดจะมีหลอดไฟ RGB ถ้าไม่ใช้งานให้ใส่คำสั่งปิดไว้ไม่งั้นมันจะทำงานเอง
– RGB = GPIO8 - ช่องต่อมอเตอร์แบบ Pin header
- ช่องต่อมอเตอร์แบบ Terminal
การใช้งานมอเตอร์
สามารถนำมอเตอร์ขนาดเล็กเช่น TT Motor หรือ N20 มาต่อได้ 2 ตัวที่ M1 และ M2 ที่ช่องต่อมอเตอร์แต่ละตัวจะระบุ GPIO ที่ใช้กำหนดทิศทางการหมุน
M1
GPIO7 | GPIO9 | ทิศทาง |
0 | 0 | หยุด |
1 | 0 | เดินหน้า |
0 | 1 | ถอยหลัง |
1 | 1 | หยุด |
M2
GPIO15 | GPIO14 | ทิศทาง |
0 | 0 | หยุด |
1 | 0 | เดินหน้า |
0 | 1 | ถอยหลัง |
1 | 1 | หยุด |
ตัวอย่างโค้ดทดสอบการทำงาน
- ปิดหลอดไฟ RGB ที่อยู่บนบอร์ดไม่ให้ทำงาน
- ต่อเซ็นเซอร์แสงที่ GPIO1 – GPIO5 แล้วอ่านค่ามาแสดงที่ Serial Monitor
- เมื่อหมุน Rotary Encoder จะเป็นการปรับความเร็วรอบมอเตอร์ ให้แสดงค่าที่จอ OLED พร้อมทั้งหมุนเซอร์โวมอเตอร์ที่ต่อกับ GPIO6 ตามรอบความเร็ว
- เมื่อกด Rotary Encoder ให้สลับโหมด เดินหน้า-ถอยหลัง-หยุด
#include <Arduino.h>
#include <Wire.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <ESP32Servo.h>
#include <Adafruit_NeoPixel.h> // <<<< เพิ่มสำหรับปิด RGB บน GPIO8
// ---------------- Pin Map ----------------
#define ENC_CLK 18 // Rotary CLK
#define ENC_DT 19 // Rotary DT
#define ENC_SW 20 // Rotary SW
#define M_A1 7 // DRV8833 AIN1
#define M_A2 9 // DRV8833 AIN2
#define M_B1 15 // DRV8833 BIN1
#define M_B2 14 // DRV8833 BIN2
#define SERVO_PIN 6 // Servo MG996R signal
#define OLED_SDA 16 // I2C SDA
#define OLED_SCL 17 // I2C SCL
// ---------- Onboard RGB (Neopixel) ----------
#define RGB_PIN 8
#define RGB_NUMPIXELS 1
Adafruit_NeoPixel rgb(RGB_NUMPIXELS, RGB_PIN, NEO_GRB + NEO_KHZ800);
// Analog inputs (GPIO1..5)
const int analogPins[5] = {1, 2, 3, 4, 5};
// --------------- OLED --------------------
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
#define OLED_RESET -1
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
// ---------------- Servo ------------------
Servo myServo;
// ------------- Motor PWM (LEDC 3.x) -----
const int PWM_FREQ = 20000; // 20 kHz
const int PWM_RES = 8; // 8-bit (0..255)
// ---------------- State ------------------
enum MotionMode { STOP = 0, FORWARD, REVERSE };
volatile MotionMode mode = STOP;
volatile int speedPct = 100; // 0..100
// Rotary polling
int lastClk = HIGH;
unsigned long lastEncMs = 0;
const unsigned long ENC_POLL_MS = 1;
// Button debounce
unsigned long lastBtnMs = 0;
const unsigned long BTN_DEBOUNCE_MS = 250;
// OLED refresh
unsigned long lastOledMs = 0;
const unsigned long OLED_MS = 100;
// Analog print
unsigned long lastAnalogMs = 0;
const unsigned long ANA_MS = 250;
// ---------------- Helpers ----------------
inline int pctToDuty(int pct) {
if (pct < 0) pct = 0;
if (pct > 100) pct = 100;
return map(pct, 0, 100, 0, 255);
}
void setMotorStop() {
ledcWrite(M_A1, 0);
ledcWrite(M_B1, 0);
ledcWrite(M_A2, 0);
ledcWrite(M_B2, 0);
digitalWrite(M_A1, LOW);
digitalWrite(M_B1, LOW);
digitalWrite(M_A2, LOW);
digitalWrite(M_B2, LOW);
}
void setMotorForward(int pct) {
const int d = pctToDuty(pct);
// เดินหน้า: A1/B1 PWM, A2/B2 LOW
ledcWrite(M_A2, 0); digitalWrite(M_A2, LOW);
ledcWrite(M_B2, 0); digitalWrite(M_B2, LOW);
ledcWrite(M_A1, d);
ledcWrite(M_B1, d);
}
void setMotorReverse(int pct) {
const int d = pctToDuty(pct);
// ถอยหลัง: A2/B2 PWM, A1/B1 LOW
ledcWrite(M_A1, 0); digitalWrite(M_A1, LOW);
ledcWrite(M_B1, 0); digitalWrite(M_B1, LOW);
ledcWrite(M_A2, d);
ledcWrite(M_B2, d);
}
void updateMotorAndLED() {
if (mode == STOP || speedPct == 0) {
setMotorStop();
} else if (mode == FORWARD) {
setMotorForward(speedPct);
} else { // REVERSE
setMotorReverse(speedPct);
}
}
void updateServo() {
// หมุน 0..90 องศา ตาม speedPct 0..100
const int angle = map(speedPct, 0, 100, 0, 90);
myServo.write(angle);
}
void updateOLED() {
display.clearDisplay();
display.setTextColor(SSD1306_WHITE);
display.setTextSize(1);
display.setCursor(0, 0);
display.println("ESP32-C6 Test Panel");
display.setTextSize(2);
display.setCursor(0, 16);
if (mode == STOP) display.println("STOP");
else if (mode == FORWARD)display.println("FWD");
else display.println("REV");
display.setTextSize(1);
display.setCursor(0, 40);
display.print("Speed: "); display.print(speedPct); display.println("%");
const int angle = map(speedPct, 0, 100, 0, 90);
display.setCursor(0, 52);
display.print("Servo: "); display.print(angle); display.println(" deg");
display.display();
}
void pollEncoder() {
if (millis() - lastEncMs < ENC_POLL_MS) return;
lastEncMs = millis();
int clk = digitalRead(ENC_CLK);
if (clk != lastClk) {
int dt = digitalRead(ENC_DT);
if (dt == clk) speedPct++; else speedPct--;
if (speedPct < 0) speedPct = 0;
if (speedPct > 100) speedPct = 100;
updateMotorAndLED();
updateServo();
}
lastClk = clk;
}
void handleButton() {
if (millis() - lastBtnMs < BTN_DEBOUNCE_MS) return;
if (digitalRead(ENC_SW) == LOW) {
lastBtnMs = millis();
if (mode == STOP) mode = FORWARD;
else if (mode == FORWARD) mode = REVERSE;
else mode = STOP;
updateMotorAndLED();
}
}
void printAnalogs() {
if (millis() - lastAnalogMs < ANA_MS) return;
lastAnalogMs = millis();
// รูปแบบ: A1=...,A2=...,A3=...,A4=...,A5=...
String line;
for (int i = 0; i < 5; i++) {
int val = analogRead(analogPins[i]);
line += "A"; line += (i + 1); line += "="; line += val;
if (i < 4) line += ",";
}
Serial.println(line);
}
// ----------------------------------------
void setup() {
Serial.begin(115200);
delay(50);
// ====== ปิด RGB (Neopixel) ที่ GPIO8 ทันที ======
rgb.begin();
rgb.clear(); // ทั้งหมด = 0,0,0
rgb.show(); // อัปเดต -> ดับไฟ
// ==============================================
// I2C + OLED
Wire.begin(OLED_SDA, OLED_SCL);
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) {
Serial.println("SSD1306 allocation failed");
} else {
display.clearDisplay(); display.display();
}
// Rotary / LED
pinMode(ENC_CLK, INPUT_PULLUP);
pinMode(ENC_DT, INPUT_PULLUP);
pinMode(ENC_SW, INPUT_PULLUP);
lastClk = digitalRead(ENC_CLK);
// 1) จอง timer สำหรับเซอร์โว (50Hz)
myServo.setPeriodHertz(50);
myServo.attach(SERVO_PIN, 500, 2500);
// 2) ตั้ง PWM มอเตอร์ (20 kHz) ด้วย LEDC 3.x
pinMode(M_A1, OUTPUT); pinMode(M_A2, OUTPUT);
pinMode(M_B1, OUTPUT); pinMode(M_B2, OUTPUT);
ledcAttach(M_A1, PWM_FREQ, PWM_RES);
ledcAttach(M_B1, PWM_FREQ, PWM_RES);
ledcAttach(M_A2, PWM_FREQ, PWM_RES);
ledcAttach(M_B2, PWM_FREQ, PWM_RES);
setMotorStop();
updateServo();
updateOLED();
Serial.println("Ready.");
}
void loop() {
pollEncoder();
handleButton();
if (millis() - lastOledMs >= OLED_MS) {
lastOledMs = millis();
updateOLED();
}
printAnalogs();
}