9 Commits

Author SHA1 Message Date
lyf
96aaeb0460 · 2026-03-28 05:03:21 +08:00
lyf
99226caf2f 1 2026-03-28 04:57:45 +08:00
lyf
24340d93f3 1 2026-03-28 04:56:40 +08:00
lyf
e8d6bbac42 1 2026-03-28 04:54:33 +08:00
lyf
f40c37c136 1 2026-03-28 04:50:38 +08:00
lyf
28827fe008 修改 2026-03-28 04:40:02 +08:00
lyf
b8dbb5aa47 xiugai 2026-03-28 04:32:08 +08:00
lyf
14c87856e7 跟新发包 2026-03-28 04:31:23 +08:00
lyf
d195deaa48 迁移入tty持续连接 2026-03-28 04:08:07 +08:00
16 changed files with 879 additions and 49 deletions

View File

@@ -1,7 +1,7 @@
CMAKE_MINIMUM_REQUIRED(VERSION 3.5) CMAKE_MINIMUM_REQUIRED(VERSION 3.5)
PROJECT(SJTU-RM-CV) PROJECT(SJTU-RM-CV)
SET(CMAKE_CXX_STANDARD 11) SET(CMAKE_CXX_STANDARD 14)
SET(CMAKE_BUILD_TYPE RELEASE) SET(CMAKE_BUILD_TYPE RELEASE)
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3") SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3")
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DPATH=\"\\\"${PROJECT_SOURCE_DIR}\\\"\"") SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DPATH=\"\\\"${PROJECT_SOURCE_DIR}\\\"\"")

View File

@@ -0,0 +1,82 @@
#ifndef CSERIALPORT_SERIALPORT_H
#define CSERIALPORT_SERIALPORT_H
#include <cstdint>
#include <cstring>
namespace itas109 {
enum class Parity {
ParityNone = 0,
ParityOdd = 1,
ParityEven = 2,
};
enum class DataBits {
DataBits5 = 5,
DataBits6 = 6,
DataBits7 = 7,
DataBits8 = 8,
};
enum class StopBits {
StopOne = 1,
StopOneAndHalf = 3,
StopTwo = 2,
};
enum class FlowControl {
FlowNone = 0,
FlowHardware = 1,
FlowSoftware = 2,
};
class CSerialPort {
public:
CSerialPort();
~CSerialPort();
// 初始化串口参数(不打开)
void init(const char* portName,
int baudRate = 115200,
Parity parity = Parity::ParityNone,
DataBits dataBits = DataBits::DataBits8,
StopBits stopBits = StopBits::StopOne,
FlowControl flowControl = FlowControl::FlowNone,
int readTimeoutMs = 1000);
// 打开串口,成功返回 true
bool open();
// 关闭串口
void close();
// 写数据,返回实际写入字节数(失败返回 -1
int writeData(const uint8_t* data, size_t length);
// 读数据,返回实际读取字节数(失败返回 -1
int readData(uint8_t* buffer, size_t maxLength);
// 返回最近一次错误码
int getLastError() const { return m_lastError; }
private:
char m_portName[256];
int m_baudRate;
Parity m_parity;
DataBits m_dataBits;
StopBits m_stopBits;
FlowControl m_flowControl;
int m_readTimeoutMs;
int m_fd; // 文件描述符
int m_lastError;
bool m_isOpen;
// termios 波特率映射
static int toBaudRate(int baud);
};
} // namespace itas109
#endif // CSERIALPORT_SERIALPORT_H

View File

@@ -0,0 +1,27 @@
#ifndef CSERIALPORT_SERIALPORTINFO_H
#define CSERIALPORT_SERIALPORTINFO_H
#include <vector>
#include <cstring>
namespace itas109 {
struct SerialPortInfo {
char portName[256];
char description[256];
SerialPortInfo() {
std::memset(portName, 0, sizeof(portName));
std::memset(description, 0, sizeof(description));
}
};
class CSerialPortInfo {
public:
// 枚举系统上所有可用串口
static std::vector<SerialPortInfo> availablePortInfos();
};
} // namespace itas109
#endif // CSERIALPORT_SERIALPORTINFO_H

View File

@@ -0,0 +1,58 @@
#ifndef SERIAL_COMM_H
#define SERIAL_COMM_H
#include <vector>
#include "CSerialPort/SerialPort.h"
#include "CSerialPort/SerialPortInfo.h"
#include <cstdio>
using namespace itas109;
// Serial port configuration
namespace SerialConfig {
constexpr int BAUD_RATE = 115200;
constexpr Parity PARITY_TYPE = Parity::ParityNone;
constexpr DataBits DATA_BITS = DataBits::DataBits8;
constexpr StopBits STOP_BITS = StopBits::StopOne;
constexpr FlowControl FLOW_CTRL = FlowControl::FlowNone;
constexpr int READ_TIMEOUT_MS = 1000;
}
class SerialComm {
private:
CSerialPort m_serialPort;
char m_portName[256];
bool m_isOpen;
public:
SerialComm();
~SerialComm();
// Find first ttyUSB device
bool findFirstTtyUSB();
// Open serial port
bool openPort();
// Close serial port
void closePort();
// Send data
bool sendData(const char* data, size_t length);
bool sendData(const uint8_t* data, size_t length);
// Receive data
int receiveData(uint8_t* buffer, size_t maxLength);
int receiveData(char* buffer, size_t maxLength);
// Check if port is open
bool isOpen() const { return m_isOpen; }
// Get current port name
const char* getPortName() const { return m_portName; }
// List all available ports
static void listAllPorts();
};
#endif // SERIAL_COMM_H

View File

@@ -0,0 +1,126 @@
#ifndef SERIAL_MANAGER_HPP
#define SERIAL_MANAGER_HPP
#include "serialComm.hpp"
#include <thread>
#include <atomic>
#include <mutex>
#include <cstdio>
#include <chrono>
class SerialManager {
private:
SerialComm m_serial;
std::thread m_connectionThread;
std::atomic<bool> m_isConnected;
std::atomic<bool> m_shouldStop;
std::mutex m_serialMutex;
int m_retryIntervalMs;
// 后台重连线程函数
void connectionThreadFunc() {
printf("[I][SerialMgr]: RETRY\n");
while (!m_shouldStop.load()) {
if (!m_isConnected.load()) {
std::lock_guard<std::mutex> lock(m_serialMutex);
if (m_serial.findFirstTtyUSB() && m_serial.openPort()) {
m_isConnected.store(true);
} else {
printf("[W][SerialMgr]: Failed, retry in %dms\n", m_retryIntervalMs);
}
}
std::this_thread::sleep_for(std::chrono::milliseconds(m_retryIntervalMs));
}
printf("[I][SerialMgr]: EXIT\n");
}
public:
// 构造函数retryIntervalMs - 重试间隔(毫秒)
SerialManager(int retryIntervalMs = 500)
: m_isConnected(false)
, m_shouldStop(false)
, m_retryIntervalMs(retryIntervalMs) {
}
~SerialManager() {
stop();
}
// 启动管理器(开始后台重连)
void start() {
if (!m_connectionThread.joinable()) {
m_shouldStop.store(false);
m_connectionThread = std::thread(&SerialManager::connectionThreadFunc, this);
printf("[I][SerialMgr]: START\n");
}
}
// 停止管理器
void stop() {
if (m_connectionThread.joinable()) {
m_shouldStop.store(true);
m_connectionThread.join();
std::lock_guard<std::mutex> lock(m_serialMutex);
m_serial.closePort();
m_isConnected.store(false);
printf("[I][SerialMgr]: STOP\n");
}
}
// 检查是否已连接
bool isConnected() const {
return m_isConnected.load();
}
// 发送数据(线程安全)
bool sendData(const char* data, size_t length) {
if (!m_isConnected.load()) {
return false;
}
std::lock_guard<std::mutex> lock(m_serialMutex);
if (!m_serial.sendData(data, length)) {
// 发送失败,标记为断开
m_isConnected.store(false);
printf("[W][SerialMgr]: Failed, mark DISCONNECT\n");
return false;
}
return true;
}
// 发送数据(字节数组)
bool sendData(const uint8_t* data, size_t length) {
return sendData(reinterpret_cast<const char*>(data), length);
}
// 接收数据(线程安全)
int receiveData(uint8_t* buffer, size_t maxLength) {
if (!m_isConnected.load()) {
return -1;
}
std::lock_guard<std::mutex> lock(m_serialMutex);
return m_serial.receiveData(buffer, maxLength);
}
// 接收数据(字符数组)
int receiveData(char* buffer, size_t maxLength) {
return receiveData(reinterpret_cast<uint8_t*>(buffer), maxLength);
}
// 获取端口名
const char* getPortName() const {
return m_serial.getPortName();
}
};
#endif // SERIAL_MANAGER_HPP

View File

@@ -0,0 +1,40 @@
#ifndef UNIFIED_MANAGER_HPP
#define UNIFIED_MANAGER_HPP
#include "serialComm.hpp"
#include <memory>
#include <thread>
#include <atomic>
#include <mutex>
#include <chrono>
// Unified device manager (Serial only)
class UnifiedDeviceManager {
private:
std::unique_ptr<SerialComm> m_serial;
std::thread m_serialReconnectThread;
std::atomic<bool> m_serialConnected;
std::atomic<bool> m_shouldStop;
std::mutex m_serialMutex;
int m_retryIntervalMs;
void serialReconnectThreadFunc();
public:
UnifiedDeviceManager(int retryIntervalMs = 500);
~UnifiedDeviceManager();
void start();
void stop();
bool isSerialConnected() const { return m_serialConnected.load(); }
// Serial operations (thread-safe)
bool sendData(const char* data, size_t length);
int receiveData(uint8_t* buffer, size_t maxLength);
};
#endif // UNIFIED_MANAGER_HPP

View File

@@ -0,0 +1,207 @@
#include "CSerialPort/SerialPort.h"
#include <fcntl.h>
#include <termios.h>
#include <unistd.h>
#include <sys/select.h>
#include <cerrno>
#include <cstring>
namespace itas109 {
CSerialPort::CSerialPort()
: m_baudRate(115200)
, m_parity(Parity::ParityNone)
, m_dataBits(DataBits::DataBits8)
, m_stopBits(StopBits::StopOne)
, m_flowControl(FlowControl::FlowNone)
, m_readTimeoutMs(1000)
, m_fd(-1)
, m_lastError(0)
, m_isOpen(false)
{
std::memset(m_portName, 0, sizeof(m_portName));
}
CSerialPort::~CSerialPort() {
close();
}
void CSerialPort::init(const char* portName,
int baudRate,
Parity parity,
DataBits dataBits,
StopBits stopBits,
FlowControl flowControl,
int readTimeoutMs)
{
std::strncpy(m_portName, portName, sizeof(m_portName) - 1);
m_portName[sizeof(m_portName) - 1] = '\0';
m_baudRate = baudRate;
m_parity = parity;
m_dataBits = dataBits;
m_stopBits = stopBits;
m_flowControl = flowControl;
m_readTimeoutMs = readTimeoutMs;
}
bool CSerialPort::open() {
if (m_isOpen) close();
m_fd = ::open(m_portName, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (m_fd < 0) {
m_lastError = errno;
return false;
}
struct termios tty;
std::memset(&tty, 0, sizeof(tty));
if (tcgetattr(m_fd, &tty) != 0) {
m_lastError = errno;
::close(m_fd);
m_fd = -1;
return false;
}
// 波特率
speed_t speed = static_cast<speed_t>(toBaudRate(m_baudRate));
cfsetispeed(&tty, speed);
cfsetospeed(&tty, speed);
// 数据位
tty.c_cflag &= ~CSIZE;
switch (m_dataBits) {
case DataBits::DataBits5: tty.c_cflag |= CS5; break;
case DataBits::DataBits6: tty.c_cflag |= CS6; break;
case DataBits::DataBits7: tty.c_cflag |= CS7; break;
case DataBits::DataBits8:
default: tty.c_cflag |= CS8; break;
}
// 停止位
if (m_stopBits == StopBits::StopTwo)
tty.c_cflag |= CSTOPB;
else
tty.c_cflag &= ~CSTOPB;
// 校验位
switch (m_parity) {
case Parity::ParityOdd:
tty.c_cflag |= PARENB;
tty.c_cflag |= PARODD;
tty.c_iflag |= (INPCK | ISTRIP);
break;
case Parity::ParityEven:
tty.c_cflag |= PARENB;
tty.c_cflag &= ~PARODD;
tty.c_iflag |= (INPCK | ISTRIP);
break;
case Parity::ParityNone:
default:
tty.c_cflag &= ~PARENB;
tty.c_iflag &= ~(INPCK | ISTRIP);
break;
}
// 流控
if (m_flowControl == FlowControl::FlowHardware)
tty.c_cflag |= CRTSCTS;
else
tty.c_cflag &= ~CRTSCTS;
if (m_flowControl == FlowControl::FlowSoftware)
tty.c_iflag |= (IXON | IXOFF | IXANY);
else
tty.c_iflag &= ~(IXON | IXOFF | IXANY);
// 本地模式 & 输入模式raw
tty.c_cflag |= (CREAD | CLOCAL);
tty.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL);
tty.c_oflag &= ~OPOST;
// 非阻塞读,超时由 select 控制
tty.c_cc[VMIN] = 0;
tty.c_cc[VTIME] = 0;
if (tcsetattr(m_fd, TCSANOW, &tty) != 0) {
m_lastError = errno;
::close(m_fd);
m_fd = -1;
return false;
}
tcflush(m_fd, TCIOFLUSH);
m_isOpen = true;
m_lastError = 0;
return true;
}
void CSerialPort::close() {
if (m_fd >= 0) {
::close(m_fd);
m_fd = -1;
}
m_isOpen = false;
}
int CSerialPort::writeData(const uint8_t* data, size_t length) {
if (!m_isOpen || m_fd < 0) {
m_lastError = EBADF;
return -1;
}
ssize_t written = ::write(m_fd, data, length);
if (written < 0) {
m_lastError = errno;
return -1;
}
tcdrain(m_fd); // 等待发送完成
return static_cast<int>(written);
}
int CSerialPort::readData(uint8_t* buffer, size_t maxLength) {
if (!m_isOpen || m_fd < 0) {
m_lastError = EBADF;
return -1;
}
// 用 select 实现超时
struct timeval tv;
tv.tv_sec = m_readTimeoutMs / 1000;
tv.tv_usec = (m_readTimeoutMs % 1000) * 1000;
fd_set fds;
FD_ZERO(&fds);
FD_SET(m_fd, &fds);
int ret = select(m_fd + 1, &fds, nullptr, nullptr, &tv);
if (ret <= 0) {
// 超时或错误
m_lastError = (ret == 0) ? ETIME : errno;
return 0;
}
ssize_t bytesRead = ::read(m_fd, buffer, maxLength);
if (bytesRead < 0) {
m_lastError = errno;
return -1;
}
m_lastError = 0;
return static_cast<int>(bytesRead);
}
int CSerialPort::toBaudRate(int baud) {
switch (baud) {
case 9600: return B9600;
case 19200: return B19200;
case 38400: return B38400;
case 57600: return B57600;
case 115200: return B115200;
case 230400: return B230400;
case 460800: return B460800;
case 921600: return B921600;
default: return B115200;
}
}
} // namespace itas109

View File

@@ -0,0 +1,35 @@
#include "CSerialPort/SerialPortInfo.h"
#include <dirent.h>
#include <cstring>
#include <string>
namespace itas109 {
std::vector<SerialPortInfo> CSerialPortInfo::availablePortInfos() {
std::vector<SerialPortInfo> result;
// 扫描 /dev 目录,找 ttyUSB / ttyCH341USB / ttyACM / ttyS 等设备
DIR* dir = opendir("/dev");
if (!dir) return result;
struct dirent* entry;
while ((entry = readdir(dir)) != nullptr) {
const char* name = entry->d_name;
if (std::strstr(name, "ttyUSB") != nullptr ||
std::strstr(name, "ttyCH341") != nullptr ||
std::strstr(name, "ttyACM") != nullptr)
{
SerialPortInfo info;
std::string fullPath = std::string("/dev/") + name;
std::strncpy(info.portName, fullPath.c_str(), sizeof(info.portName) - 1);
std::strncpy(info.description, name, sizeof(info.description) - 1);
result.push_back(info);
}
}
closedir(dir);
return result;
}
} // namespace itas109

View File

@@ -38,6 +38,12 @@ void ArmorFinder::antiTop() {
// 通过两次装甲角度为零的时间差计算陀螺旋转周期 // 通过两次装甲角度为零的时间差计算陀螺旋转周期
// 根据旋转周期计算下一次装甲出现在角度为零的时间点 // 根据旋转周期计算下一次装甲出现在角度为零的时间点
if (getPointLength(last_box.getCenter() - target_box.getCenter()) > last_box.rect.height * 1.5) { if (getPointLength(last_box.getCenter() - target_box.getCenter()) > last_box.rect.height * 1.5) {
sum_yaw = sum_pitch = 0;
double dx = target_box.rect.x + target_box.rect.width / 2.0 - IMAGE_CENTER_X;
double dy = target_box.rect.y + target_box.rect.height / 2.0 - IMAGE_CENTER_Y;
last_yaw = dx;
last_pitch = dy;
auto front_time = getFrontTime(time_seq, angle_seq); auto front_time = getFrontTime(time_seq, angle_seq);
auto once_periodms = getTimeIntervalms(front_time, last_front_time); auto once_periodms = getTimeIntervalms(front_time, last_front_time);
// if (abs(once_periodms - top_periodms[-1]) > 50) { // if (abs(once_periodms - top_periodms[-1]) > 50) {

View File

@@ -54,7 +54,9 @@ ArmorFinder::ArmorFinder(uint8_t &color, Serial &u, const string &paras_folder,
anti_switch_cnt(0), anti_switch_cnt(0),
classifier(paras_folder), classifier(paras_folder),
contour_area(0), contour_area(0),
tracking_cnt(0) { tracking_cnt(0),
last_yaw(0), last_pitch(0),
sum_yaw(0), sum_pitch(0) {
} }
void ArmorFinder::run(cv::Mat &src) { void ArmorFinder::run(cv::Mat &src) {
@@ -75,6 +77,9 @@ void ArmorFinder::run(cv::Mat &src) {
tracker->init(src, target_box.rect); tracker->init(src, target_box.rect);
state = TRACKING_STATE; state = TRACKING_STATE;
tracking_cnt = 0; tracking_cnt = 0;
last_yaw = target_box.rect.x + target_box.rect.width / 2.0 - IMAGE_CENTER_X;
last_pitch = target_box.rect.y + target_box.rect.height / 2.0 - IMAGE_CENTER_Y;
sum_yaw = sum_pitch = 0;
LOGM(STR_CTR(WORD_LIGHT_CYAN, "into track")); LOGM(STR_CTR(WORD_LIGHT_CYAN, "into track"));
} }
} }
@@ -82,6 +87,8 @@ void ArmorFinder::run(cv::Mat &src) {
case TRACKING_STATE: case TRACKING_STATE:
if (!stateTrackingTarget(src) || ++tracking_cnt > 100) { // 最多追踪100帧图像 if (!stateTrackingTarget(src) || ++tracking_cnt > 100) { // 最多追踪100帧图像
state = SEARCHING_STATE; state = SEARCHING_STATE;
last_yaw = last_pitch = 0;
sum_yaw = sum_pitch = 0;
LOGM(STR_CTR(WORD_LIGHT_YELLOW, "into search!")); LOGM(STR_CTR(WORD_LIGHT_YELLOW, "into search!"));
} }
break; break;
@@ -93,6 +100,11 @@ end:
if(is_anti_top) { // 判断当前是否为反陀螺模式 if(is_anti_top) { // 判断当前是否为反陀螺模式
antiTop(); antiTop();
}else if(target_box.rect != cv::Rect2d()) { }else if(target_box.rect != cv::Rect2d()) {
if (last_box.rect == cv::Rect2d()) {
sum_yaw = sum_pitch = 0;
last_yaw = target_box.rect.x + target_box.rect.width / 2.0 - IMAGE_CENTER_X;
last_pitch = target_box.rect.y + target_box.rect.height / 2.0 - IMAGE_CENTER_Y;
}
anti_top_cnt = 0; anti_top_cnt = 0;
time_seq.clear(); time_seq.clear();
angle_seq.clear(); angle_seq.clear();

View File

@@ -5,42 +5,58 @@
#include <armor_finder/armor_finder.h> #include <armor_finder/armor_finder.h>
#include <config/setconfig.h> #include <config/setconfig.h>
#include <log.h> #include <log.h>
#include <string>
#include <cstdio>
static bool sendTarget(Serial &serial, double x, double y, double z, uint16_t shoot_delay) { // ANGLE_SCALE: 角度单位换算系数。发出的整数 = yaw_deg / ANGLE_SCALE
static short x_tmp, y_tmp, z_tmp; // 例: 1.0f → 单位为度; 0.01f → 单位为厘度(精度更高)
uint8_t buff[10]; static constexpr float ANGLE_SCALE = 1.0f;
static bool sendTarget(Serial &serial, double yaw_deg, double pitch_deg, double dist,
uint16_t shoot_delay, char type = 'r') {
// static short x_tmp, y_tmp, z_tmp;
// uint8_t buff[10];
#ifdef WITH_COUNT_FPS #ifdef WITH_COUNT_FPS
static time_t last_time = time(nullptr); static time_t last_time = time(nullptr);
static int fps; static int fps;
time_t t = time(nullptr); time_t t = time(nullptr);
if (last_time != t) { if (last_time != t) {
last_time = t; last_time = t;
cout << "Armor: fps:" << fps << ", (" << x << "," << y << "," << z << ")" << endl; cout << "Armor: fps:" << fps << ", yaw=" << yaw_deg
<< " pitch=" << pitch_deg << " dist=" << dist << endl;
fps = 0; fps = 0;
} }
fps += 1; fps += 1;
#endif #endif
#define MINMAX(value, min, max) value = ((value) < (min)) ? (min) : ((value) > (max) ? (max) : (value)) // ---- 新格式: 字符串帧 ----
// 格式: "s <yaw_int> <pitch_int> <dist> <shoot_delay> e\n"
int16_t yaw_tmp = static_cast<int16_t>(yaw_deg / ANGLE_SCALE);
int16_t pitch_tmp = static_cast<int16_t>(pitch_deg / ANGLE_SCALE);
char buf[64];
std::snprintf(buf, sizeof(buf), "s %d %d %.1f %u e\n",
(int)yaw_tmp, (int)pitch_tmp, dist, (unsigned)shoot_delay);
std::string frame(buf);
return serial.WriteData(reinterpret_cast<const uint8_t*>(frame.data()), frame.size());
x_tmp = static_cast<short>(x * (32768 - 1) / 100);
y_tmp = static_cast<short>(y * (32768 - 1) / 100);
z_tmp = static_cast<short>(z * (32768 - 1) / 1000);
buff[0] = 's'; // ---- 原始二进制打包(已注释)----
buff[1] = static_cast<char>((x_tmp >> 8) & 0xFF); // static short x_tmp, y_tmp, z_tmp;
buff[2] = static_cast<char>((x_tmp >> 0) & 0xFF); // uint8_t buff[10];
buff[3] = static_cast<char>((y_tmp >> 8) & 0xFF); // x_tmp = static_cast<short>(yaw_deg * (32768 - 1) / 100);
buff[4] = static_cast<char>((y_tmp >> 0) & 0xFF); // y_tmp = static_cast<short>(pitch_deg * (32768 - 1) / 100);
buff[5] = static_cast<char>((z_tmp >> 8) & 0xFF); // z_tmp = static_cast<short>(dist * (32768 - 1) / 1000);
buff[6] = static_cast<char>((z_tmp >> 0) & 0xFF); // buff[0] = 's';
buff[7] = static_cast<char>((shoot_delay >> 8) & 0xFF); // buff[1] = static_cast<char>((x_tmp >> 8) & 0xFF);
buff[8] = static_cast<char>((shoot_delay >> 0) & 0xFF); // buff[2] = static_cast<char>((x_tmp >> 0) & 0xFF);
buff[9] = 'e'; // buff[3] = static_cast<char>((y_tmp >> 8) & 0xFF);
// if(buff[7]<<8 | buff[8]) // buff[4] = static_cast<char>((y_tmp >> 0) & 0xFF);
// cout << (buff[7]<<8 | buff[8]) << endl; // buff[5] = static_cast<char>((z_tmp >> 8) & 0xFF);
return serial.WriteData(buff, sizeof(buff)); // buff[6] = static_cast<char>((z_tmp >> 0) & 0xFF);
// buff[7] = static_cast<char>((shoot_delay >> 8) & 0xFF);
// buff[8] = static_cast<char>((shoot_delay >> 0) & 0xFF);
// buff[9] = 'e';
// return serial.WriteData(buff, sizeof(buff));
} }
bool ArmorFinder::sendBoxPosition(uint16_t shoot_delay) { bool ArmorFinder::sendBoxPosition(uint16_t shoot_delay) {
@@ -53,8 +69,12 @@ bool ArmorFinder::sendBoxPosition(uint16_t shoot_delay) {
double dy = rect.y + rect.height / 2 - IMAGE_CENTER_Y; double dy = rect.y + rect.height / 2 - IMAGE_CENTER_Y;
// PID // PID
#define MAX_I 100 // 这里的数值可以根据实际调试情况进一步微调
sum_yaw += dx; sum_yaw += dx;
sum_pitch += dy; sum_pitch += dy;
sum_yaw = (sum_yaw > MAX_I) ? MAX_I : (sum_yaw < -MAX_I ? -MAX_I : sum_yaw);
sum_pitch = (sum_pitch > MAX_I) ? MAX_I : (sum_pitch < -MAX_I ? -MAX_I : sum_pitch);
float yaw_I_component = YAW_AIM_KI * sum_yaw; float yaw_I_component = YAW_AIM_KI * sum_yaw;
float pitch_I_component = PITCH_AIM_KI * sum_pitch; float pitch_I_component = PITCH_AIM_KI * sum_pitch;

127
armor/src/serialComm.cpp Normal file
View File

@@ -0,0 +1,127 @@
#include "serialComm.hpp"
#include <cstring>
#include <cstdio>
SerialComm::SerialComm() : m_isOpen(false) {
std::memset(m_portName, 0, sizeof(m_portName));
m_serialPort.init(
"",
SerialConfig::BAUD_RATE,
SerialConfig::PARITY_TYPE,
SerialConfig::DATA_BITS,
SerialConfig::STOP_BITS,
SerialConfig::FLOW_CTRL,
SerialConfig::READ_TIMEOUT_MS
);
}
SerialComm::~SerialComm() {
closePort();
}
bool SerialComm::findFirstTtyUSB() {
std::vector<SerialPortInfo> portInfos = CSerialPortInfo::availablePortInfos();
for (const auto& info : portInfos) {
const char* portStr = info.portName;
if (std::strstr(portStr, "ttyCH341USB") != nullptr) {
std::strncpy(m_portName, portStr, sizeof(m_portName) - 1);
m_portName[sizeof(m_portName) - 1] = '\0';
printf("[I][SERIAL]: ttyUSB device found: %s\n", m_portName);
return true;
}
}
return false;
}
bool SerialComm::openPort() {
if (std::strlen(m_portName) == 0) {
printf("[E][Serial]: Port name is empty, call findFirstTtyUSB() first\n");
return false;
}
m_serialPort.init(
m_portName,
SerialConfig::BAUD_RATE,
SerialConfig::PARITY_TYPE,
SerialConfig::DATA_BITS,
SerialConfig::STOP_BITS,
SerialConfig::FLOW_CTRL,
SerialConfig::READ_TIMEOUT_MS
);
if (!m_serialPort.open()) {
printf("[E][Serial]: Failed to open port %s\n", m_portName);
printf("[E][Serial]: Error code: %d\n", m_serialPort.getLastError());
m_isOpen = false;
return false;
}
m_isOpen = true;
printf("[I][Serial]: Port opened successfully: %s\n", m_portName);
printf("[I][Serial]: Baud rate: %d\n", SerialConfig::BAUD_RATE);
printf("[I][Serial]: Data bits: 8\n");
printf("[I][Serial]: Stop bits: 1\n");
printf("[I][Serial]: Parity: None\n");
return true;
}
void SerialComm::closePort() {
if (m_isOpen) {
m_serialPort.close();
m_isOpen = false;
printf("[I][Serial]: Port closed: %s\n", m_portName);
}
}
bool SerialComm::sendData(const char* data, size_t length) {
return sendData(reinterpret_cast<const uint8_t*>(data), length);
}
bool SerialComm::sendData(const uint8_t* data, size_t length) {
if (!m_isOpen) {
printf("[E][Serial]: Port not open\n");
return false;
}
int bytesWritten = m_serialPort.writeData(data, length);
if (bytesWritten > 0) {
printf("[I][Serial]: Sent %d bytes\n", bytesWritten);
return true;
} else {
printf("[E][Serial]: Failed to send data\n");
return false;
}
}
int SerialComm::receiveData(char* buffer, size_t maxLength) {
return receiveData(reinterpret_cast<uint8_t*>(buffer), maxLength);
}
int SerialComm::receiveData(uint8_t* buffer, size_t maxLength) {
if (!m_isOpen) {
printf("[E][Serial]: Port not open\n");
return -1;
}
int bytesRead = m_serialPort.readData(buffer, maxLength);
if (bytesRead > 0) {
printf("[I][Serial]: Received %d bytes\n", bytesRead);
}
return bytesRead;
}
void SerialComm::listAllPorts() {
std::vector<SerialPortInfo> portInfos = CSerialPortInfo::availablePortInfos();
printf("[I][Serial]: Available ports:\n");
for (const auto& info : portInfos) {
printf("[I][Serial]: - %s\n", info.portName);
}
}

View File

@@ -0,0 +1,92 @@
#include "unifiedManager.hpp"
#include <cstdio>
UnifiedDeviceManager::UnifiedDeviceManager(int retryIntervalMs)
: m_serial(std::make_unique<SerialComm>())
, m_serialConnected(false)
, m_shouldStop(false)
, m_retryIntervalMs(retryIntervalMs)
{
printf("[I][Managr]: Unified device manager created\n");
}
UnifiedDeviceManager::~UnifiedDeviceManager() {
stop();
}
void UnifiedDeviceManager::serialReconnectThreadFunc() {
printf("[I][Managr]: Serial reconnect thread started\n");
while (!m_shouldStop.load()) {
if (!m_serialConnected.load()) {
printf("[I][Managr]: Attempting to connect serial port...\n");
std::lock_guard<std::mutex> lock(m_serialMutex);
if (m_serial->findFirstTtyUSB() && m_serial->openPort()) {
m_serialConnected.store(true);
printf("[I][Managr]: Serial port connected successfully\n");
} else {
printf("[W][Managr]: Serial connection failed, retry in %dms\n",
m_retryIntervalMs);
}
}
std::this_thread::sleep_for(std::chrono::milliseconds(m_retryIntervalMs));
}
printf("[I][Managr]: Serial reconnect thread stopped\n");
}
void UnifiedDeviceManager::start() {
printf("[I][Managr]: Starting unified device manager\n");
m_shouldStop.store(false);
if (!m_serialReconnectThread.joinable()) {
m_serialReconnectThread = std::thread(&UnifiedDeviceManager::serialReconnectThreadFunc, this);
}
printf("[I][Managr]: Unified device manager started\n");
}
void UnifiedDeviceManager::stop() {
printf("[I][Managr]: Stopping unified device manager\n");
m_shouldStop.store(true);
if (m_serialReconnectThread.joinable()) {
m_serialReconnectThread.join();
std::lock_guard<std::mutex> lock(m_serialMutex);
m_serial->closePort();
m_serialConnected.store(false);
}
printf("[I][Managr]: Unified device manager stopped\n");
}
bool UnifiedDeviceManager::sendData(const char* data, size_t length) {
if (!m_serialConnected.load()) {
return false;
}
std::lock_guard<std::mutex> lock(m_serialMutex);
if (!m_serial->sendData(data, length)) {
m_serialConnected.store(false);
printf("[W][Managr]: Serial send failed, marked as disconnected\n");
return false;
}
return true;
}
int UnifiedDeviceManager::receiveData(uint8_t* buffer, size_t maxLength) {
if (!m_serialConnected.load()) {
return -1;
}
std::lock_guard<std::mutex> lock(m_serialMutex);
return m_serial->receiveData(buffer, maxLength);
}

View File

@@ -20,6 +20,7 @@
#include <options.h> #include <options.h>
#include <additions.h> #include <additions.h>
#include <config/setconfig.h> #include <config/setconfig.h>
#include "serialManager.hpp"
#define DO_NOT_CNT_TIME #define DO_NOT_CNT_TIME
@@ -41,7 +42,8 @@ McuData mcu_data = { // 单片机端回传结构体
WrapperHead *video = nullptr; // 云台摄像头视频源 WrapperHead *video = nullptr; // 云台摄像头视频源
Serial serial(115200); // 串口对象 Serial serial(115200); // 串口对象(旧版,供 armor_finder/energy 使用)
SerialManager serialManager; // TTY 串口自动恢复管理器
uint8_t last_state = ARMOR_STATE; // 上次状态,用于初始化 uint8_t last_state = ARMOR_STATE; // 上次状态,用于初始化
// 自瞄主程序对象 // 自瞄主程序对象
ArmorFinder armor_finder(mcu_data.enemy_color, serial, PROJECT_DIR"/tools/para/", mcu_data.anti_top); ArmorFinder armor_finder(mcu_data.enemy_color, serial, PROJECT_DIR"/tools/para/", mcu_data.anti_top);
@@ -50,6 +52,7 @@ Energy energy(serial, mcu_data.enemy_color);
int main(int argc, char *argv[]) { int main(int argc, char *argv[]) {
processOptions(argc, argv); // 处理命令行参数 processOptions(argc, argv); // 处理命令行参数
serialManager.start(); // 启动 TTY 串口自动重连线程
thread receive(uartReceive, &serial); // 开启串口接收线程 thread receive(uartReceive, &serial); // 开启串口接收线程
int from_camera = 1; // 根据条件选择视频源 int from_camera = 1; // 根据条件选择视频源

View File

@@ -41,7 +41,7 @@
#endif #endif
#ifndef YAW_AIM_KD #ifndef YAW_AIM_KD
#define YAW_AIM_KD (0.4) #define YAW_AIM_KD (0.1)
#endif #endif
#ifndef YAW_AIM_KP #ifndef YAW_AIM_KP
#define YAW_AIM_KP (0.75) #define YAW_AIM_KP (0.75)

View File

@@ -177,6 +177,8 @@ bool Serial::ReadData(unsigned char *buffer, unsigned int length) {
#elif defined(Linux) || defined(Darwin) #elif defined(Linux) || defined(Darwin)
#include <string.h> #include <string.h>
#include <thread>
#include <chrono>
using namespace std; using namespace std;
@@ -189,17 +191,10 @@ string get_uart_dev_name() {
Serial::Serial(int nSpeed, char nEvent, int nBits, int nStop) : Serial::Serial(int nSpeed, char nEvent, int nBits, int nStop) :
nSpeed(nSpeed), nEvent(nEvent), nBits(nBits), nStop(nStop) { nSpeed(nSpeed), nEvent(nEvent), nBits(nBits), nStop(nStop) {
if (wait_uart) { LOGM("Waiting for serial port...");
LOGM("Wait for serial be ready!"); while (!InitPort(nSpeed, nEvent, nBits, nStop))
while (!InitPort(nSpeed, nEvent, nBits, nStop)); std::this_thread::sleep_for(std::chrono::milliseconds(500));
LOGM("Port set successfully!"); LOGM("Port set successfully!");
} else {
if (InitPort(nSpeed, nEvent, nBits, nStop)) {
LOGM("Port set successfully!");
} else {
LOGE("Port set fail!");
}
}
} }
Serial::~Serial() { Serial::~Serial() {
@@ -228,18 +223,18 @@ bool Serial::InitPort(int nSpeed, char nEvent, int nBits, int nStop) {
bool Serial::WriteData(const unsigned char *pData, unsigned int length) { bool Serial::WriteData(const unsigned char *pData, unsigned int length) {
int cnt = 0, curr = 0; int cnt = 0, curr = 0;
if (fd <= 0) { if (fd <= 0) {
if(wait_uart){ LOGE("Serial offline! Reconnecting...");
InitPort(nSpeed, nEvent, nBits, nStop); while (!InitPort(nSpeed, nEvent, nBits, nStop))
} std::this_thread::sleep_for(std::chrono::milliseconds(500));
return false; return false;
} }
while ((curr = write(fd, pData + cnt, length - cnt)) > 0 && (cnt += curr) < length); while ((curr = write(fd, pData + cnt, length - cnt)) > 0 && (cnt += curr) < length);
if (curr < 0) { if (curr < 0) {
LOGE("Serial offline!"); LOGE("Serial write error! Reconnecting...");
close(fd); close(fd);
if (wait_uart) { fd = -1;
InitPort(nSpeed, nEvent, nBits, nStop); while (!InitPort(nSpeed, nEvent, nBits, nStop))
} std::this_thread::sleep_for(std::chrono::milliseconds(500));
return false; return false;
} }
return true; return true;
@@ -249,11 +244,11 @@ bool Serial::ReadData(unsigned char *buffer, unsigned int length) {
int cnt = 0, curr = 0; int cnt = 0, curr = 0;
while ((curr = read(fd, buffer + cnt, length - cnt)) > 0 && (cnt += curr) < length); while ((curr = read(fd, buffer + cnt, length - cnt)) > 0 && (cnt += curr) < length);
if (curr < 0) { if (curr < 0) {
LOGE("Serial offline!"); LOGE("Serial read error! Reconnecting...");
close(fd); close(fd);
if (wait_uart) { fd = -1;
InitPort(nSpeed, nEvent, nBits, nStop); while (!InitPort(nSpeed, nEvent, nBits, nStop))
} std::this_thread::sleep_for(std::chrono::milliseconds(500));
return false; return false;
} }
return true; return true;