8.14
【目标任务】
这个帖子是小智语音控制ESP32 S3 双电机小车|极简MCP插件教程- Makelog(造物记)的续集,重点在于解决前面帖子中的一个bug---前进后退左转右转时的时间限制。上一个小车可以在运动中调速度,并且立即实现,可以加上时间的精准控制,可是持续运动的功能受限。
这次我还换了小车底盘,这个底盘有两个万向轮,可以原地转圈圈如同西域的胡旋舞。
【编程环境配置】
让小智语音控制ESP32 S3点灯|极简MCP插件教程- Makelog(造物记)

K10小智的摄像头,有拍照识图功能,所以这次不用语音了,换个新花样。
材料清单
- K10小智AI X1
- L298N电机驱动模块 X1
- TT电机 X2
- ESP32 S3开发板 X1
- 锂电池组合 X1
- 小车底盘 X1
步骤1 小车接线
关于L298N,在上个帖子中有详述。

我的小车接线:


下图中经典的中国红色电机模块给搞成了黑色。

组装好之后:

步骤2 代码编写
编程环境配置:
让小智语音控制ESP32 S3点灯|极简MCP插件教程- Makelog(造物记)
1. 硬件控制
电机驱动:使用L298N模块控制左右两个直流电机,支持前进、后退、左转、右转和停止五种状态,通过PWM调节速度(0-255)。
引脚定义:电机使能信号(ENA/ENB)和方向控制引脚(IN1-IN4)对应Arduino的GPIO引脚。
🌐 2. 网络通信
WiFi连接:通过WiFi库连接指定热点(SSID: CMCC-QuYY),为远程控制提供网络基础。
WebSocket通信:使用WebSocketMCP库连接至远程控制平台(api.xiaozhi.me),通过Token认证建立双向通信通道。
🕹️ 3. 远程控制功能
指令解析:注册两个工具供远程调用:
car_control:执行运动指令(前进/后退/左转/右转/停止),可设定持续时间和速度。
set_speed:独立调节小车速度。
JSON协议:指令通过JSON格式传输(如{"action":"forward", "duration":1000, "speed":200}),使用ArduinoJson解析。
控制指令:
方向控制:前进、后退、左转、右转、停止。
运动时间控制:如前进3秒,左转半秒等。
速度调节:可以先调速,再发运行指令。也可以在运行中调速,立即执行。
代码如下:(由仰望esp32 S3+L298N+舵机小车代码修改过来)
#include <WiFi.h>
#include <WebSocketMCP.h>
#include <L298N.h>
#include <ArduinoJson.h>
// 电机引脚定义
#define ENA 14
#define IN1 12
#define IN2 13
#define ENB 17
#define IN3 15
#define IN4 16
// 硬件对象初始化
L298N leftMotor(ENA, IN1, IN2);
L298N rightMotor(ENB, IN3, IN4);
// 网络配置
const char* ssid = "******";
const char* password = "******";
const char* mcpEndpoint = "ws://api.xiaozhi.me/mcp/?token=******";
WebSocketMCP mcpClient;
// 控制状态机
enum CarState { STOP, FORWARD, BACKWARD, LEFT, RIGHT };
CarState currentState = STOP;
int currentSpeed = 150; // 默认速度(0-255)
// 超时控制核心变量
unsigned long actionStartTime = 0; // 当前动作开始时间
int actionDuration = 0; // 用户设定持续时间(0=持续执行)
unsigned long lastCmdTime = 0; // 最后有效指令时间戳
// 函数前置声明
void registerMcpTools();
void controlCar(CarState state, int speed = -1);
void setServoAngle(int angle);
// 连接状态回调
void onConnectionStatus(bool connected) {
if (connected) {
Serial.println("[MCP] 已连接到服务器");
registerMcpTools();
} else {
Serial.println("[MCP] 与服务器断开连接");
}
}
// 核心控制函数
void controlCar(CarState state, int speed) {
if (speed >= 0) currentSpeed = speed;
// 电机驱动逻辑
switch (state) {
case FORWARD:
leftMotor.setSpeed(currentSpeed);
rightMotor.setSpeed(currentSpeed);
leftMotor.forward();
rightMotor.forward();
break;
case BACKWARD:
leftMotor.setSpeed(currentSpeed);
rightMotor.setSpeed(currentSpeed);
leftMotor.backward();
rightMotor.backward();
break;
case LEFT:
leftMotor.setSpeed(currentSpeed);
rightMotor.setSpeed(currentSpeed);
leftMotor.backward();
rightMotor.forward();
break;
case RIGHT:
leftMotor.setSpeed(currentSpeed);
rightMotor.setSpeed(currentSpeed);
leftMotor.forward();
rightMotor.backward();
break;
case STOP:
leftMotor.stop();
rightMotor.stop();
actionDuration = 0; // 清除超时标志
break;
}
// 状态更新与调试输出
currentState = state;
const char* stateNames[] = {"停止", "前进", "后退", "左转", "右转"};
Serial.printf("动作: %s | 速度: %d | 模式: %s\n",
stateNames[state],
currentSpeed,
actionDuration > 0 ? "限时模式" : "持续模式");
}
// 注册MCP控制工具
void registerMcpTools() {
// 运动控制工具
mcpClient.registerTool(
"car_control",
"控制小车运动(forward/backward/left/right/stop)",
"{\"type\":\"object\",\"properties\":{"
"\"action\":{\"type\":\"string\",\"enum\":[\"forward\",\"backward\",\"left\",\"right\",\"stop\"]},"
"\"duration\":{\"type\":\"integer\",\"description\":\"持续时间(ms,0表示持续执行)\"},"
"\"speed\":{\"type\":\"integer\",\"minimum\":0,\"maximum\":255}}"
",\"required\":[\"action\"]}",
[](const String& args) {
DynamicJsonDocument doc(256);
deserializeJson(doc, args);
String action = doc["action"].as<String>();
int duration = doc["duration"] | 0; // 默认0=持续执行
int speed = doc["speed"] | -1;
// 指令转换
CarState targetState = STOP;
if (action == "forward") targetState = FORWARD;
else if (action == "backward") targetState = BACKWARD;
else if (action == "left") targetState = LEFT;
else if (action == "right") targetState = RIGHT;
// 超时参数记录
if (duration > 0) {
actionStartTime = millis();
actionDuration = duration;
} else {
actionDuration = 0; // 持续执行模式
}
// 执行动作
controlCar(targetState, speed);
// 关键修复:收到指令时刷新安全计时器
lastCmdTime = millis();
return WebSocketMCP::ToolResponse("{\"status\":\"executing\",\"action\":\"" + action + "\"}");
}
);
// 速度调节工具
mcpClient.registerTool(
"set_speed",
"设置小车速度(0-255)",
"{\"type\":\"object\",\"properties\":{\"speed\":{\"type\":\"integer\",\"minimum\":0,\"maximum\":255}},\"required\":[\"speed\"]}",
[](const String& args) {
DynamicJsonDocument doc(128);
deserializeJson(doc, args);
currentSpeed = doc["speed"];
if (currentState != STOP) {
controlCar(currentState);
}
// 刷新安全计时器
lastCmdTime = millis();
return WebSocketMCP::ToolResponse("{\"speed\":" + String(currentSpeed) + "}");
}
);
}
void setup() {
Serial.begin(115200);
// 电机初始状态
controlCar(STOP);
// WiFi连接
Serial.printf("连接WiFi: %s\n", ssid);
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.printf("\nWiFi已连接! IP: %s\n", WiFi.localIP().toString());
// MCP客户端启动
mcpClient.begin(mcpEndpoint, onConnectionStatus);
lastCmdTime = millis(); // 初始化安全计时器
}
void loop() {
mcpClient.loop();
// 模式1:限时动作检测
if (actionDuration > 0 && currentState != STOP) {
if (millis() - actionStartTime >= actionDuration) {
controlCar(STOP);
Serial.println("[系统] 动作时间到达");
actionDuration = 0;
}
}
// 安全保护:30秒无新指令停止
if (millis() - lastCmdTime > 30000 && currentState != STOP) {
controlCar(STOP);
Serial.println("[安全] 30秒无指令自动停车");
}
delay(10);
}
上传,测试通过,实现全部预想功能。
小智后台:

评论