From 64a4c8ae436a2b6ab087fb067f67b72be5ba90cc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E7=8E=96=E5=8F=81?= Date: Mon, 16 Dec 2024 00:16:06 +0800 Subject: [PATCH] optimize: SPP Bluetooth -> BLE --- src/main.cpp | 196 +++++++++++++++++++++++++++++---------------------- 1 file changed, 111 insertions(+), 85 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index 1e09460..9b176df 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1,5 +1,8 @@ #include -#include +#include +#include +#include +#include #define STATUS_LED 2 @@ -38,15 +41,11 @@ #define TURN_RATIO 0.6 // 转向时的速度比例 #define SPEED_INCREMENT 10 // 速度增量 -// 全局变量 -int currentSpeed = 0; // 当前速度 -int turnOffset = 0; // 转向偏移量 (-100 到 100) -bool isMoving = false; // 运动状态 -bool isTurning = false; // 转向状态 +// Nordic UART Service UUID +#define SERVICE_UUID "6E400001-B5A3-F393-E0A9-E50E24DCCA9E" +#define CHARACTERISTIC_UUID_RX "6E400002-B5A3-F393-E0A9-E50E24DCCA9E" +#define CHARACTERISTIC_UUID_TX "6E400003-B5A3-F393-E0A9-E50E24DCCA9E" -BluetoothSerial SerialBT; - -// 在全局变量定义区域添加以下内容 #define PACKET_R_HEAD 0x00 #define PACKET_R_TAIL 0xFF #define PACKET_T_HEAD 0x01 @@ -59,6 +58,17 @@ BluetoothSerial SerialBT; #define CMD_MOTOR_MOVE_CONTROL 0x20 #define CMD_MOTOR_ROTATE_CONTROL 0x21 +// 全局变量 +int currentSpeed = 0; // 当前速度 +int turnOffset = 0; // 转向偏移量 (-100 到 100) +bool isMoving = false; // 运动状态 +bool isTurning = false; // 转向状态 + +// BLE 相关 +BLEServer *pServer = nullptr; +BLECharacteristic *pTxCharacteristic = nullptr; +bool deviceConnected = false; + // 数据包缓冲区 uint8_t packetBuffer[PACKET_MAX_LENGTH]; int packetIndex = 0; @@ -69,6 +79,38 @@ bool isReceivingPacket = false; unsigned long lastLedToggle = 0; // 上次LED切换状态的时间 bool ledState = false; // LED当前状态 +void processSerialIncomingByte(uint8_t incomingByte, BLECharacteristic &characteristic); + +class CarBLEServerCallbacks : public BLEServerCallbacks +{ + void onConnect(BLEServer *pServer) + { + deviceConnected = true; + }; + + void onDisconnect(BLEServer *pServer) + { + deviceConnected = false; + // 重新开始广播 + pServer->getAdvertising()->start(); + } +}; + +class CarBLECharacteristicCallbacks : public BLECharacteristicCallbacks +{ + void onWrite(BLECharacteristic *pCharacteristic) + { + std::string rxValue = pCharacteristic->getValue(); + if (rxValue.length() > 0) + { + for (int i = 0; i < rxValue.length(); i++) + { + processSerialIncomingByte((uint8_t)rxValue[i], *pTxCharacteristic); + } + } + } +}; + void floatToBytes(float val, uint8_t *bytes) { union @@ -107,7 +149,6 @@ void motorControl(int pwmPin, int in1Pin, int in2Pin, int speed) analogWrite(pwmPin, speed); } - float getDistance() { digitalWrite(HC_SR04_TRIG, HIGH); @@ -118,18 +159,32 @@ float getDistance() return distance; } -u_char getSerialBTStatus() -{ - return SerialBT.connected() ? 0x01 : 0x00; -} - void setup() { // 初始化串口 Serial.begin(115200); - // 初始化蓝牙 - SerialBT.begin("WhiteTiger"); + // 初始化 BLE + BLEDevice::init("WhiteTiger"); + pServer = BLEDevice::createServer(); + pServer->setCallbacks(new CarBLEServerCallbacks()); + + BLEService *pService = pServer->createService(SERVICE_UUID); + + // 创建 RX 特征值 (用于接收数据) + BLECharacteristic *pRxCharacteristic = pService->createCharacteristic( + CHARACTERISTIC_UUID_RX, + BLECharacteristic::PROPERTY_WRITE); + pRxCharacteristic->setCallbacks(new CarBLECharacteristicCallbacks()); + + // 创建 TX 特征值 (用于发送数据) + pTxCharacteristic = pService->createCharacteristic( + CHARACTERISTIC_UUID_TX, + BLECharacteristic::PROPERTY_NOTIFY); + pTxCharacteristic->addDescriptor(new BLE2902()); + + pService->start(); + pServer->getAdvertising()->start(); // 设置引脚模式 pinMode(STATUS_LED, OUTPUT); @@ -155,50 +210,49 @@ void setup() pinMode(HC_SR04_ECHO, INPUT); } -void handleSerialPacket(uint8_t *packet, int length, Stream &serial) +void handleSerialPacket(uint8_t *packet, int length, BLECharacteristic &characteristic) { - if (length < 4) - return; // 最小包长度:包头(1) + 长度(1) + 指令(1) + 包尾(1) + if (!deviceConnected || length < 4) + return; uint8_t packetLength = packet[1]; // 获取长度 uint8_t cmd = packet[2]; // 获取指令 uint8_t direction, speed, time; float distance; - - uint8_t transmitBuffer[PACKET_MAX_LENGTH]; + uint8_t buffer[PACKET_MAX_LENGTH]; // 用于存储要发送的数据 + int bufferIndex = 0; switch (cmd) { case CMD_GET_BT_STATUS: Serial.println("CMD_GET_BT_STATUS"); - // 回复状态 - serial.write(PACKET_T_HEAD); - serial.write(0x05); // 包体长度 - serial.write(CMD_GET_BT_STATUS); - serial.write(getSerialBTStatus()); - serial.write(PACKET_T_TAIL); + // 构建响应数据 + buffer[0] = PACKET_T_HEAD; + buffer[1] = 0x05; + buffer[2] = CMD_GET_BT_STATUS; + buffer[3] = (uint8_t)(deviceConnected ? 0x01 : 0x00); + buffer[4] = PACKET_T_TAIL; + characteristic.setValue(buffer, 5); + characteristic.notify(); break; case CMD_GET_DISTANCE: - Serial.println("CMD_GET_DISTANCE"); distance = getDistance(); - Serial.printf("distance = %f\n", distance); - floatToBytes(distance, transmitBuffer); - // 回复距离 - serial.write(PACKET_T_HEAD); - serial.write(0x08); // 包体长度 - serial.write(CMD_GET_DISTANCE); - serial.write(transmitBuffer, 4); - serial.write(PACKET_T_TAIL); + Serial.println("CMD_GET_DISTANCE, distance: " + String(distance)); + // 构建响应数据 + buffer[0] = PACKET_T_HEAD; + buffer[1] = 0x08; + buffer[2] = CMD_GET_DISTANCE; + floatToBytes(distance, &buffer[3]); + buffer[7] = PACKET_T_TAIL; + characteristic.setValue(buffer, 8); + characteristic.notify(); break; case CMD_MOTOR_MOVE_CONTROL: - // 获取方向和速度 direction = packet[3]; speed = packet[4]; - - Serial.printf("CMD_MOTOR_MOVE_CONTROL: direction = 0x%02X, speed = %d\n", direction, speed); - + Serial.println("CMD_MOTOR_MOVE_CONTROL, direction: " + String(direction) + ", speed: " + String(speed)); // 移动 if (direction == 0x00) { @@ -207,64 +261,52 @@ void handleSerialPacket(uint8_t *packet, int length, Stream &serial) motorControl(MOTOR_C_PWMA, MOTOR_C_AIN1, MOTOR_C_AIN2, 0); motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, 0); } - // 前进 - if (direction == 0x01) + else if (direction == 0x01) { motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, speed); motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, speed); motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, speed); motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, speed); } - // 后退 - if (direction == 0x02) + else if (direction == 0x02) { motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, -speed); motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, -speed); motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, -speed); motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, -speed); } - break; case CMD_MOTOR_ROTATE_CONTROL: - // 获取方向和时间 direction = packet[3]; time = packet[4]; - - // 原地旋转 - Serial.printf("CMD_MOTOR_ROTATE_CONTROL: direction = 0x%02X, time = %d\n", direction, time); + Serial.println("CMD_MOTOR_ROTATE_CONTROL, direction: " + String(direction) + ", time: " + String(time)); // 顺时针 if (direction == 0x00) { - // 左侧电机向前转 - motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, 255); // 左前 - motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, 255); // 左后 - // 右侧电机向后转 - motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, -255); // 右后 - motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, -255); // 右前 + motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, 255); + motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, 255); + motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, -255); + motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, -255); } - // 逆时针 - if (direction == 0x01) + else if (direction == 0x01) { - // 左侧电机向后转 - motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, -255); // 左前 - motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, -255); // 左后 - // 右侧电机向前转 - motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, 255); // 右后 - motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, 255); // 右前 + motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, -255); + motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, -255); + motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, 255); + motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, 255); } break; default: - // 未知指令处理 break; } } -void processSerialIncomingByte(uint8_t incomingByte, Stream &serial) +void processSerialIncomingByte(uint8_t incomingByte, BLECharacteristic &characteristic) { static uint8_t expectedLength = 0; @@ -294,7 +336,7 @@ void processSerialIncomingByte(uint8_t incomingByte, Stream &serial) isReceivingPacket = false; if (incomingByte == PACKET_R_TAIL) { - handleSerialPacket(packetBuffer, packetIndex + 1, serial); + handleSerialPacket(packetBuffer, packetIndex + 1, *pTxCharacteristic); } } } @@ -307,14 +349,12 @@ void processSerialIncomingByte(uint8_t incomingByte, Stream &serial) void updateStatusLED() { - if (SerialBT.connected()) + if (deviceConnected) { - // 蓝牙已连接,LED常亮 digitalWrite(STATUS_LED, HIGH); } else { - // 蓝牙未连接,LED慢闪 unsigned long currentMillis = millis(); if (currentMillis - lastLedToggle >= LED_FLASH_INTERVAL) { @@ -327,19 +367,5 @@ void updateStatusLED() void loop() { - if (SerialBT.available()) - { - uint8_t incomingByte = SerialBT.read(); - processSerialIncomingByte(incomingByte, SerialBT); - Serial.printf("BT Received: 0x%02X\n", incomingByte); - } - - if (Serial.available()) - { - uint8_t incomingByte = Serial.read(); - processSerialIncomingByte(incomingByte, Serial); - Serial.printf("UART Received: 0x%02X\n", incomingByte); - } - - updateStatusLED(); // 更新LED状态 + updateStatusLED(); }