feat: single wheel control

This commit is contained in:
玖叁 2024-12-18 17:31:35 +08:00
parent 1fb8e6f30b
commit 3452b05333
2 changed files with 45 additions and 2 deletions

View File

@ -74,6 +74,25 @@
控制示例 `00 06 21 01 01 FF` 控制示例 `00 06 21 01 01 FF`
### 单轮控制 `0x22`
| 轮数据 | 含义 |
| -------- | ---- |
| 0x00 | 左前轮 |
| 0x01 | 左后轮 |
| 0x02 | 右后轮 |
| 0x03 | 右前轮 |
| 方向数据 | 含义 |
| -------- | ---- |
| 0x00 | 停止 |
| 0x01 | 顺时针 |
| 0x02 | 逆时针 |
包体 `00 07 22 轮 方向 速度 FF`
控制示例 `00 07 22 01 01 01 FF`
## 设置 ## 设置
### 设置转向灵敏度 `0x30` ### 设置转向灵敏度 `0x30`

View File

@ -21,7 +21,7 @@
#define CMD_GET_DISTANCE 0x12 #define CMD_GET_DISTANCE 0x12
#define CMD_MOTOR_MOVE_CONTROL 0x20 #define CMD_MOTOR_MOVE_CONTROL 0x20
#define CMD_MOTOR_ROTATE_CONTROL 0x21 #define CMD_MOTOR_ROTATE_CONTROL 0x21
#define CMD_MOTOR_SINGLE_CONTROL 0x22
// 全局变量 // 全局变量
int currentSpeed = 0; // 当前速度 int currentSpeed = 0; // 当前速度
int turnOffset = 0; // 转向偏移量 (-100 到 100) int turnOffset = 0; // 转向偏移量 (-100 到 100)
@ -164,6 +164,7 @@ public:
file.close(); file.close();
} }
}; };
bool CarStorage::isMounted = false;
void setup() void setup()
{ {
@ -226,7 +227,7 @@ void handleSerialPacket(uint8_t *packet, int length, BLECharacteristic &characte
uint8_t packetLength = packet[1]; // 获取长度 uint8_t packetLength = packet[1]; // 获取长度
uint8_t cmd = packet[2]; // 获取指令 uint8_t cmd = packet[2]; // 获取指令
uint8_t direction, speed, time; uint8_t direction, speed, time, wheel;
float distance; float distance;
uint8_t buffer[PACKET_MAX_LENGTH]; // 用于存储要发送的数据 uint8_t buffer[PACKET_MAX_LENGTH]; // 用于存储要发送的数据
int bufferIndex = 0; int bufferIndex = 0;
@ -322,6 +323,29 @@ void handleSerialPacket(uint8_t *packet, int length, BLECharacteristic &characte
} }
break; break;
case CMD_MOTOR_SINGLE_CONTROL:
wheel = packet[3];
direction = packet[4];
speed = packet[5];
Serial.println("CMD_MOTOR_SINGLE_CONTROL, wheel: " + String(wheel) + ", direction: " + String(direction) + ", speed: " + String(speed));
// 单轮控制
switch (wheel)
{
case 0x00:
motorControl(MOTOR_A_PWMA, MOTOR_A_AIN1, MOTOR_A_AIN2, speed);
break;
case 0x01:
motorControl(MOTOR_B_PWMB, MOTOR_B_BIN2, MOTOR_B_BIN1, speed);
break;
case 0x02:
motorControl(MOTOR_C_PWMA, MOTOR_C_AIN2, MOTOR_C_AIN1, speed);
break;
case 0x03:
motorControl(MOTOR_D_PWMB, MOTOR_D_BIN1, MOTOR_D_BIN2, speed);
break;
}
break;
default: default:
break; break;
} }