20浏览
查看: 20|回复: 0

[项目] FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目

[复制链接]
本帖最后由 云天 于 2025-7-28 13:52 编辑

【项目概述】

本项目旨在通过 FireBeetle ESP32-P4 开发板和小智 AI 平台实现一个智能小车,能够通过语音指令控制其运动状态。小车使用 TB6612FNG 微型双路直流电机驱动模块驱动两个 N20 减速电机,并通过行空板 K10 安装小智 AI 固件实现语音交互功能。整个项目结合了硬件开发、嵌入式编程和人工智能技术,具有较高的实用性和趣味性。
【项目亮点】

本项目的核心亮点之一是成功集成并应用了 xiaozhi-mcp库。该库是专为 ESP32 设备设计的,用于无缝接入小智 AI 平台的 MCP(模型上下文协议)服务器。通过 xiaozhi-mcp库,我们能够以极低的开发成本实现Esp32P4设备与小智 AI 平台的稳定通信,支持复杂的 JSON-RPC 协议,同时具备自动重连机制,确保了通信的高可靠性和稳定性。
【硬件设计】

1. FireBeetle ESP32-P4 开发板
FireBeetle ESP32-P4 是一款功能强大的开发板,具备丰富的 GPIO 引脚和强大的处理能力,适合用于物联网和嵌入式项目。在本项目中,我们使用其引脚 20、21、22 和 23 分别连接 TB6612FNG 驱动模块的控制引脚,用于控制电机的运动状态。

2. TB6612FNG 微型双路直流电机驱动模块
TB6612FNG 是一款双路全桥驱动芯片,单通道最大连续驱动电流可达 1.2A,峰值 2A/3.2A(连续脉冲/单脉冲),能够驱动微型直流电机。其控制逻辑简单,仅需 4 根管脚即可实现双路电机控制,适合与 Arduino 等控制器配合使用。

3. 行空板 K10
行空板 K10 是一款支持小智 AI 固件的开发板,具备语音交互功能。通过安装小智 AI 固件并配网,接入小智AI控制台配置智能体,从而将语音指令发送到小智 AI 服务器,实现对 ESP32-P4 小车的远程控制。
FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图7

【软件设计】

1. Arduino IDE 编程
使用 Arduino IDE 2.3.6 编写 ESP32-P4 的控制程序,加载 `xiaozhi-mcp` 库以实现与小智 AI 平台的通信。程序通过 WebSocket 连接到小智 AI 的 MCP 服务器,并注册工具以接收语音指令,进而控制小车的运动状态。
FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图1
2. 小智 AI 平台
小智 AI 提供了一个强大的语音交互平台,支持通过 MCP 协议与外部设备通信。通过在行空板 K10 上安装小智 AI 固件并配网,可以获取专属的 MCP 接入点,实现语音指令的发送和接收。
FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图6
【项目实现】

1. 硬件连接
- 将 TB6612FNG 的 DIR1 引脚连接到 ESP32-P4 的引脚 20,PWM1 引脚连接到引脚 21。
- 将 TB6612FNG 的 DIR2 引脚连接到 ESP32-P4 的引脚 22,PWM2 引脚连接到引脚 23。
- 将两个 N20 减速电机分别连接到 TB6612FNG 的 M1 和 M2 接口。
- 将行空板 K10 安装小智 AI 固件并配网,获取 MCP 接入点。FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图3FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图5FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图4

2. 软件配置
- 在 Arduino IDE 中安装 `xiaozhi-mcp` 库。
- 编写 ESP32-P4 的控制程序,配置 WiFi 和 MCP 服务器地址,注册运动控制工具。
- 在小智 AI 平台上配置语音指令,将其映射到对应的 MCP 工具。


FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图2
FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图9
3. 程序逻辑
- 初始化 WiFi 和 MCP 客户端。
- 注册运动控制工具,接收语音指令。
- 根据语音指令控制电机的运动状态(前进、后退、停止、左转、右转)。
- 通过状态 LED 显示当前连接状态。
  1. #include <Arduino.h>
  2. #include <WiFi.h>
  3. #include <WebSocketMCP.h>
  4. /********** 配置项 ***********/
  5. // WiFi设置
  6. const char* WIFI_SSID = "sxs";
  7. const char* WIFI_PASS = "smj080823";
  8. // WebSocket MCP服务器地址
  9. const char* MCP_ENDPOINT = "wss://api.xiaozhi.me/mcp/?token=eyJhbGciOiJFUzI1NiIsInR5cCI6IkpXVCJ9.eyJ1c2VySWQiOjEyODIzNSwiYWdlbnRJZCI6MTkwMjQsImVuZHBvaW50SWQiOiJhZ2VudF8xOTAyNCIsInB1cnBvc2UiOiJtY3AtZW5kcG9pbnQiLCJpYXQiOjE3NTM2MjQ4NDV9.LRuzeBUypjuc-NFuMYJb8Q7aUTn3GLY9xPNYFHLS3KMrkvV9nKHMJt1GvLy36kEq_oqPMnNjdbG7jchF5ZaXbw";
  10. // 调试信息
  11. #define DEBUG_SERIAL Serial
  12. #define DEBUG_BAUD_RATE 115200
  13. // LED控制引脚定义(用于状态指示和工具控制)
  14. #define LED_PIN 3  // ESP32板载LED
  15. const int motor1M = 20;  // 电机1方向控制
  16. const int motor1E = 21;  // 电机1速度控制
  17. const int motor2M = 22; // 电机2方向控制
  18. const int motor2E = 23; // 电机2速度控制
  19. /********** 全局变量 ***********/
  20. WebSocketMCP mcpClient;
  21. // 缓冲区管理
  22. #define MAX_INPUT_LENGTH 1024
  23. char inputBuffer[MAX_INPUT_LENGTH];
  24. int inputBufferIndex = 0;
  25. bool newCommandAvailable = false;
  26. // 连接状态
  27. bool wifiConnected = false;
  28. bool mcpConnected = false;
  29. /********** 函数声明 ***********/
  30. void setupWifi();
  31. void onMcpOutput(const String &message);
  32. void onMcpError(const String &error);
  33. void onMcpConnectionChange(bool connected);
  34. void processSerialCommands();
  35. void blinkLed(int times, int delayMs);
  36. void registerMcpTools();
  37. void setup() {
  38.   // 初始化串口
  39.   DEBUG_SERIAL.begin(DEBUG_BAUD_RATE);
  40.   DEBUG_SERIAL.println("\n\n[ESP32 MCP客户端] 初始化...");
  41.   
  42.   // 初始化LED
  43.   pinMode(LED_PIN, OUTPUT);
  44.   pinMode(motor1M, OUTPUT);
  45.   pinMode(motor1E, OUTPUT);
  46.   pinMode(motor2M, OUTPUT);
  47.   pinMode(motor2E, OUTPUT);
  48.   pinMode(3, OUTPUT);
  49.   digitalWrite(LED_PIN, LOW);
  50.   
  51.   // 连接WiFi
  52.   setupWifi();
  53.   
  54.   // 初始化MCP客户端
  55.   if (mcpClient.begin(MCP_ENDPOINT, onMcpConnectionChange)) {
  56.     DEBUG_SERIAL.println("[ESP32 MCP客户端] 初始化成功,尝试连接到MCP服务器...");
  57.   } else {
  58.     DEBUG_SERIAL.println("[ESP32 MCP客户端] 初始化失败!");
  59.   }
  60.   
  61.   // 显示帮助信息
  62.   DEBUG_SERIAL.println("\n使用说明:");
  63.   DEBUG_SERIAL.println("- 通过串口控制台输入命令并回车发送");
  64.   DEBUG_SERIAL.println("- 从MCP服务器接收的消息将显示在串口控制台上");
  65.   DEBUG_SERIAL.println("- 输入"help"查看可用命令");
  66.   DEBUG_SERIAL.println();
  67. }
  68. void loop() {
  69.   // 处理MCP客户端
  70.   mcpClient.loop();
  71.   
  72.   // 处理来自串口的命令
  73.   processSerialCommands();
  74.   
  75.   // 状态LED显示
  76.   if (!wifiConnected) {
  77.     // WiFi未连接: 快速闪烁
  78.     blinkLed(1, 100);
  79.   } else if (!mcpConnected) {
  80.     // WiFi已连接但MCP未连接: 慢闪
  81.     blinkLed(1, 500);
  82.   } else {
  83.     // 全部连接成功: LED亮起
  84.     digitalWrite(LED_PIN, HIGH);
  85.   }
  86. }
  87. /**
  88. * 设置WiFi连接
  89. */
  90. void setupWifi() {
  91.   DEBUG_SERIAL.print("[WiFi] 连接到 ");
  92.   DEBUG_SERIAL.println(WIFI_SSID);
  93.   
  94.   // 开始连接
  95.   WiFi.mode(WIFI_STA);
  96.   WiFi.begin(WIFI_SSID, WIFI_PASS);
  97.   
  98.   // 等待连接
  99.   int attempts = 0;
  100.   while (WiFi.status() != WL_CONNECTED && attempts < 20) {
  101.     delay(500);
  102.     DEBUG_SERIAL.print(".");
  103.     attempts++;
  104.   }
  105.   
  106.   if (WiFi.status() == WL_CONNECTED) {
  107.     wifiConnected = true;
  108.     DEBUG_SERIAL.println();
  109.     DEBUG_SERIAL.println("[WiFi] 连接成功!");
  110.     DEBUG_SERIAL.print("[WiFi] IP地址: ");
  111.     DEBUG_SERIAL.println(WiFi.localIP());
  112.   } else {
  113.     wifiConnected = false;
  114.     DEBUG_SERIAL.println();
  115.     DEBUG_SERIAL.println("[WiFi] 连接失败! 将继续尝试...");
  116.   }
  117. }
  118. /**
  119. * MCP输出回调函数(stdout替代)
  120. */
  121. void onMcpOutput(const String &message) {
  122.   DEBUG_SERIAL.print("[MCP输出] ");
  123.   DEBUG_SERIAL.println(message);
  124. }
  125. /**
  126. * MCP错误回调函数(stderr替代)
  127. */
  128. void onMcpError(const String &error) {
  129.   DEBUG_SERIAL.print("[MCP错误] ");
  130.   DEBUG_SERIAL.println(error);
  131. }
  132. /**
  133. * 注册MCP工具
  134. * 在连接成功后注册工具
  135. */
  136. void registerMcpTools() {
  137.   DEBUG_SERIAL.println("[MCP] 注册工具...");
  138.   
  139.   // 注册LED控制工具
  140.   mcpClient.registerTool(
  141.     "led_blink",  // 工具名称
  142.     "控制ESP32P4 车辆运动状态", // 工具描述
  143.     "{"properties":{"state":{"title":"车辆运动状态","type":"string","enum":["前进","后退","停止","左转","右转"]}},"required":["state"],"title":"MotorControlArguments","type":"object"}",  // 输入schema
  144.     [](const String& args) {
  145.       // 解析参数
  146.       DEBUG_SERIAL.println("[工具] 运动控制: " + args);
  147.       DynamicJsonDocument doc(256);
  148.       DeserializationError error = deserializeJson(doc, args);
  149.       
  150.       if (error) {
  151.         // 返回错误响应
  152.         WebSocketMCP::ToolResponse response("{"success":false,"error":"无效的参数格式"}", true);
  153.         return response;
  154.       }
  155.       
  156.       String state = doc["state"].as<String>();
  157.       DEBUG_SERIAL.println("[工具] 运动控制: " + state);
  158.       
  159.       // 运动控制
  160.       if (state == "前进") {
  161.         digitalWrite(motor1M, HIGH);
  162.         analogWrite(motor1E, 200);
  163.         digitalWrite(motor2M, LOW);
  164.         analogWrite(motor2E, 200);
  165.         DEBUG_SERIAL.println("[工具] 运动控制: 已" + state);
  166.       } else if (state == "后退") {
  167.         digitalWrite(motor1M, LOW);
  168.         analogWrite(motor1E, 200);
  169.         digitalWrite(motor2M, HIGH);
  170.         analogWrite(motor2E, 200);
  171.         
  172.         DEBUG_SERIAL.println("[工具] 运动控制: 已" + state);
  173.       } else if (state == "停止") {
  174.         digitalWrite(motor1M, LOW);
  175.         analogWrite(motor1E, 0);
  176.         digitalWrite(motor2M, LOW);
  177.         analogWrite(motor2E, 0);
  178.         DEBUG_SERIAL.println("[工具] 运动控制: 已" + state);
  179.       } else if (state == "左转") {
  180.         digitalWrite(motor1M, LOW);
  181.         analogWrite(motor1E, 200);
  182.         digitalWrite(motor2M, LOW);
  183.         analogWrite(motor2E, 200);
  184.         DEBUG_SERIAL.println("[工具] 运动控制: 已" + state);
  185.       }else if (state == "右转") {
  186.         digitalWrite(motor1M, HIGH);
  187.         analogWrite(motor1E, 200);
  188.         digitalWrite(motor2M, HIGH);
  189.         analogWrite(motor2E, 200);
  190.         
  191.         DEBUG_SERIAL.println("[工具] 运动控制: 已" + state);
  192.       }
  193.       
  194.       // 返回成功响应
  195.       String resultJson = "{"success":true,"state":"" + state + ""}";
  196.       return WebSocketMCP::ToolResponse(resultJson);
  197.     }
  198.   );
  199.   DEBUG_SERIAL.println("[MCP] 运动控制工具已注册");
  200.   
  201. }
  202. /**
  203. * MCP连接状态变化回调函数
  204. */
  205. void onMcpConnectionChange(bool connected) {
  206.   mcpConnected = connected;
  207.   if (connected) {
  208.     DEBUG_SERIAL.println("[MCP] 已连接到MCP服务器");
  209.     // 连接成功后注册工具
  210.     registerMcpTools();
  211.   } else {
  212.     DEBUG_SERIAL.println("[MCP] 与MCP服务器断开连接");
  213.   }
  214. }
  215. /**
  216. * 处理来自串口的命令
  217. */
  218. void processSerialCommands() {
  219.   // 检查是否有串口数据
  220.   while (DEBUG_SERIAL.available() > 0) {
  221.     char inChar = (char)DEBUG_SERIAL.read();
  222.    
  223.     // 处理回车或换行
  224.     if (inChar == '\n' || inChar == '\r') {
  225.       if (inputBufferIndex > 0) {
  226.         // 添加字符串结束符
  227.         inputBuffer[inputBufferIndex] = '\0';
  228.         
  229.         // 处理命令
  230.         String command = String(inputBuffer);
  231.         command.trim();
  232.         
  233.         if (command.length() > 0) {
  234.           if (command == "help") {
  235.             printHelp();
  236.           } else if (command == "status") {
  237.             printStatus();
  238.           } else if (command == "reconnect") {
  239.             DEBUG_SERIAL.println("正在重新连接...");
  240.             mcpClient.disconnect();
  241.           } else if (command == "tools") {
  242.             // 显示已注册工具
  243.             DEBUG_SERIAL.println("已注册工具数量: " + String(mcpClient.getToolCount()));
  244.           } else {
  245.             // 将命令发送到MCP服务器(stdin替代)
  246.             if (mcpClient.isConnected()) {
  247.               mcpClient.sendMessage(command);
  248.               DEBUG_SERIAL.println("[发送] " + command);
  249.             } else {
  250.               DEBUG_SERIAL.println("未连接到MCP服务器,无法发送命令");
  251.             }
  252.           }
  253.         }
  254.         
  255.         // 重置缓冲区
  256.         inputBufferIndex = 0;
  257.       }
  258.     }
  259.     // 处理退格键
  260.     else if (inChar == '\b' || inChar == 127) {
  261.       if (inputBufferIndex > 0) {
  262.         inputBufferIndex--;
  263.         DEBUG_SERIAL.print("\b \b"); // 退格、空格、再退格
  264.       }
  265.     }
  266.     // 处理普通字符
  267.     else if (inputBufferIndex < MAX_INPUT_LENGTH - 1) {
  268.       inputBuffer[inputBufferIndex++] = inChar;
  269.       DEBUG_SERIAL.print(inChar); // Echo
  270.     }
  271.   }
  272. }
  273. /**
  274. * 打印帮助信息
  275. */
  276. void printHelp() {
  277.   DEBUG_SERIAL.println("可用命令:");
  278.   DEBUG_SERIAL.println("  help     - 显示此帮助信息");
  279.   DEBUG_SERIAL.println("  status   - 显示当前连接状态");
  280.   DEBUG_SERIAL.println("  reconnect - 重新连接到MCP服务器");
  281.   DEBUG_SERIAL.println("  tools    - 查看已注册工具");
  282.   DEBUG_SERIAL.println("  其他任何文本将直接发送到MCP服务器");
  283. }
  284. /**
  285. * 打印当前状态
  286. */
  287. void printStatus() {
  288.   DEBUG_SERIAL.println("当前状态:");
  289.   DEBUG_SERIAL.print("  WiFi: ");
  290.   DEBUG_SERIAL.println(wifiConnected ? "已连接" : "未连接");
  291.   if (wifiConnected) {
  292.     DEBUG_SERIAL.print("  IP地址: ");
  293.     DEBUG_SERIAL.println(WiFi.localIP());
  294.     DEBUG_SERIAL.print("  信号强度: ");
  295.     DEBUG_SERIAL.println(WiFi.RSSI());
  296.   }
  297.   DEBUG_SERIAL.print("  MCP服务器: ");
  298.   DEBUG_SERIAL.println(mcpConnected ? "已连接" : "未连接");
  299. }
  300. /**
  301. * LED闪烁函数
  302. */
  303. void blinkLed(int times, int delayMs) {
  304.   static int blinkCount = 0;
  305.   static unsigned long lastBlinkTime = 0;
  306.   static bool ledState = false;
  307.   static int lastTimes = 0;
  308.   if (times == 0) {
  309.     digitalWrite(LED_PIN, LOW);
  310.     blinkCount = 0;
  311.     lastTimes = 0;
  312.     return;
  313.   }
  314.   if (lastTimes != times) {
  315.     blinkCount = 0;
  316.     lastTimes = times;
  317.     ledState = false;
  318.     lastBlinkTime = millis();
  319.   }
  320.   unsigned long now = millis();
  321.   if (blinkCount < times * 2) {
  322.     if (now - lastBlinkTime > delayMs) {
  323.       lastBlinkTime = now;
  324.       ledState = !ledState;
  325.       digitalWrite(LED_PIN, ledState ? HIGH : LOW);
  326.       blinkCount++;
  327.     }
  328.   } else {
  329.     digitalWrite(LED_PIN, LOW);
  330.     blinkCount = 0;
  331.     lastTimes = 0;
  332.   }
  333. }
复制代码

【项目成果】

通过本项目,我们成功实现了一个可以通过语音指令控制运动状态的智能小车。用户可以通过行空板 K10 上的小智 AI 发出语音指令,如“前进”、“后退”、“左转”等,小车会根据指令做出相应的动作。项目结合了硬件开发、嵌入式编程和人工智能技术,具有较高的创新性和实用性。

FireBeetle 2 ESP32-P4 和小智 AI 的智能小车项目图8

【演示视频】





您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

为本项目制作心愿单
购买心愿单
心愿单 编辑
[[wsData.name]]

硬件清单

  • [[d.name]]
btnicon
我也要做!
点击进入购买页面
上海智位机器人股份有限公司 沪ICP备09038501号-4 备案 沪公网安备31011502402448

© 2013-2025 Comsenz Inc. Powered by Discuz! X3.4 Licensed

mail