|
|
@@ -0,0 +1,802 @@
|
|
|
+#include <opencv2/opencv.hpp>
|
|
|
+#include <zmq.hpp>
|
|
|
+#include <vector>
|
|
|
+#include <chrono>
|
|
|
+#include <thread>
|
|
|
+#include <iostream>
|
|
|
+#include <fcntl.h>
|
|
|
+#include <termios.h>
|
|
|
+#include <unistd.h>
|
|
|
+#include <sstream>
|
|
|
+#include <iomanip>
|
|
|
+#include <cmath>
|
|
|
+#include <sys/socket.h>
|
|
|
+#include <arpa/inet.h>
|
|
|
+#include <netinet/in.h>
|
|
|
+// #include "ConfigManager.h" // or the correct path to your ConfigManager header
|
|
|
+#include "SimpleConfig.h" // 确保包含配置文件管理器
|
|
|
+
|
|
|
+// UDP配置
|
|
|
+// const char *UDP_IP = "10.10.60.146"; // 目标IP地址
|
|
|
+// const int UDP_PORT = 1234; // 目标端口号
|
|
|
+struct GPSData {
|
|
|
+ std::string timestamp; // UTC时间
|
|
|
+ double latitude; // 纬度
|
|
|
+ double longitude; // 经度
|
|
|
+ double altitude; // 海拔
|
|
|
+ double speed_knots; // 速度(节)
|
|
|
+ double speed_ms; // 速度(米/秒)
|
|
|
+ int quality; // 定位质量
|
|
|
+ int satellites; // 卫星数量
|
|
|
+ double yaw; // 偏航角(0~359.9°,真北方向)
|
|
|
+};
|
|
|
+
|
|
|
+bool parseGPHDT(const std::string &line, GPSData &gps) {
|
|
|
+ std::vector <std::string> tokens;
|
|
|
+ std::string token;
|
|
|
+ std::istringstream tokenStream(line);
|
|
|
+
|
|
|
+ while (std::getline(tokenStream, token, ',')) {
|
|
|
+ tokens.push_back(token);
|
|
|
+ }
|
|
|
+
|
|
|
+ // 检查是否为有效的 GPHDT 语句
|
|
|
+ if (tokens.size() < 2 || tokens[0] != "$GPHDT") {
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ try {
|
|
|
+ gps.yaw = std::stod(tokens[1]); // 提取偏航角
|
|
|
+ return true;
|
|
|
+ }
|
|
|
+ catch (...) {
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+bool parseGPGGA(const std::string &nmea, GPSData &gps) {
|
|
|
+ // 重置GPS数据
|
|
|
+ gps = GPSData();
|
|
|
+
|
|
|
+ if (nmea.empty() || nmea.find("$GPGGA") != 0) {
|
|
|
+ std::cerr << "[GPS] 无效的GPGGA起始符" << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ std::vector <std::string> tokens;
|
|
|
+ std::stringstream ss(nmea);
|
|
|
+ std::string token;
|
|
|
+
|
|
|
+ // std::cout << "Raw " << tokens << std::endl;
|
|
|
+
|
|
|
+ while (getline(ss, token, ',')) {
|
|
|
+ tokens.push_back(token);
|
|
|
+ }
|
|
|
+
|
|
|
+ if (tokens.size() < 15) {
|
|
|
+ std::cerr << "[GPS] 字段不足,实际数量: " << tokens.size() << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ try {
|
|
|
+ // 解析时间戳
|
|
|
+ if (!tokens[1].empty()) {
|
|
|
+ gps.timestamp = tokens[1];
|
|
|
+ }
|
|
|
+
|
|
|
+ // 解析纬度和经度
|
|
|
+ if (!tokens[2].empty() && !tokens[3].empty()) {
|
|
|
+ double lat = std::stod(tokens[2]);
|
|
|
+ double lat_deg = floor(lat / 100);
|
|
|
+ double lat_min = lat - lat_deg * 100;
|
|
|
+ gps.latitude = lat_deg + lat_min / 60.0;
|
|
|
+ if (tokens[3] == "S")
|
|
|
+ gps.latitude *= -1;
|
|
|
+ }
|
|
|
+
|
|
|
+ if (!tokens[4].empty() && !tokens[5].empty()) {
|
|
|
+ double lon = std::stod(tokens[4]);
|
|
|
+ double lon_deg = floor(lon / 100);
|
|
|
+ double lon_min = lon - lon_deg * 100;
|
|
|
+ gps.longitude = lon_deg + lon_min / 60;
|
|
|
+ if (tokens[5] == "W")
|
|
|
+ gps.longitude *= -1;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 解析质量指标和卫星数量
|
|
|
+ if (!tokens[6].empty())
|
|
|
+ gps.quality = std::stoi(tokens[6]);
|
|
|
+ if (!tokens[7].empty())
|
|
|
+ gps.satellites = std::stoi(tokens[7]);
|
|
|
+
|
|
|
+ // 解析海拔高度(MSL)
|
|
|
+ if (!tokens[9].empty()) {
|
|
|
+ gps.altitude = std::stod(tokens[9]);
|
|
|
+ }
|
|
|
+
|
|
|
+ // 解析高程异常值(Geoid Separation)
|
|
|
+ if (!tokens[11].empty()) {
|
|
|
+ double geoid_separation = std::stod(tokens[11]);
|
|
|
+ gps.altitude += geoid_separation; // 修正真实海拔高度
|
|
|
+ }
|
|
|
+
|
|
|
+ // 即使 quality=0(无效定位),仍然返回 true
|
|
|
+ if (gps.quality == 0) {
|
|
|
+ // std::cerr << "[GPS] 警告: 无效定位 (quality=0)" << std::endl;
|
|
|
+ }
|
|
|
+
|
|
|
+ return true; // 总是返回 true,即使定位无效
|
|
|
+ }
|
|
|
+ catch (const std::exception &e) {
|
|
|
+ std::cerr << "[GPS] 解析异常: " << e.what() << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+bool parseGPVTG(const std::string &nmea, GPSData &gps) {
|
|
|
+ if (nmea.empty() || nmea.find("$GPVTG") != 0) {
|
|
|
+ std::cerr << "[GPS] 无效的GPVTG起始符" << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ std::vector <std::string> tokens;
|
|
|
+ std::stringstream ss(nmea);
|
|
|
+ std::string token;
|
|
|
+
|
|
|
+ while (getline(ss, token, ',')) {
|
|
|
+ tokens.push_back(token);
|
|
|
+ }
|
|
|
+
|
|
|
+ if (tokens.size() < 10) {
|
|
|
+ std::cerr << "[GPS] GPVTG字段不足,实际数量: " << tokens.size() << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ try {
|
|
|
+ // 解析速度(节)
|
|
|
+ if (!tokens[5].empty()) {
|
|
|
+ gps.speed_knots = std::stod(tokens[5]);
|
|
|
+ }
|
|
|
+
|
|
|
+ // 解析速度(m/s)
|
|
|
+ if (!tokens[7].empty()) {
|
|
|
+ gps.speed_ms = std::stod(tokens[7]) / 3.6;
|
|
|
+ }
|
|
|
+
|
|
|
+ return true;
|
|
|
+ }
|
|
|
+ catch (const std::exception &e) {
|
|
|
+ std::cerr << "[GPS] GPVTG解析异常: " << e.what() << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+// 视频流采集和UDP发送函数
|
|
|
+void videoStreamUDP(const SimpleConfig &config) {
|
|
|
+
|
|
|
+ if (!config.getNetwork().udp.enabled || !config.getDevices().camera.enabled) {
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ const auto &network = config.getNetwork();
|
|
|
+ const auto &camera = config.getDevices().camera;
|
|
|
+ // 使用配置中的IP和端口
|
|
|
+ std::string UDP_IP = network.udp.target_ip;
|
|
|
+ int UDP_PORT = network.udp.target_port;
|
|
|
+ std::cout << UDP_IP << std::endl;
|
|
|
+ std::cout << UDP_PORT << std::endl;
|
|
|
+ // 创建UDP套接字
|
|
|
+ int sock = socket(AF_INET, SOCK_DGRAM, 0);
|
|
|
+ if (sock < 0) {
|
|
|
+ std::cerr << "无法创建UDP套接字" << std::endl;
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 设置目标地址
|
|
|
+ struct sockaddr_in dest_addr;
|
|
|
+ memset(&dest_addr, 0, sizeof(dest_addr));
|
|
|
+ dest_addr.sin_family = AF_INET;
|
|
|
+ dest_addr.sin_port = htons(UDP_PORT);
|
|
|
+ if (inet_pton(AF_INET, UDP_IP.c_str(), &dest_addr.sin_addr) <= 0) {
|
|
|
+ std::cerr << "无效的IP地址" << std::endl;
|
|
|
+ close(sock);
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ cv::VideoCapture cap(camera.device_index);
|
|
|
+
|
|
|
+ if (!cap.isOpened()) {
|
|
|
+ std::cerr << "无法打开摄像头!" << std::endl;
|
|
|
+ close(sock);
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ cap.set(cv::CAP_PROP_FRAME_WIDTH, camera.width);
|
|
|
+ cap.set(cv::CAP_PROP_FRAME_HEIGHT, camera.height);
|
|
|
+ cv::Mat frame;
|
|
|
+ std::vector <uchar> buffer;
|
|
|
+
|
|
|
+ while (true) {
|
|
|
+ cap >> frame;
|
|
|
+ if (frame.empty())
|
|
|
+ break;
|
|
|
+
|
|
|
+ // 压缩图像
|
|
|
+ std::vector<int> params = {cv::IMWRITE_JPEG_QUALITY, camera.jpeg_quality};
|
|
|
+ cv::imencode(".jpg", frame, buffer, params);
|
|
|
+
|
|
|
+ // 通过UDP发送数据
|
|
|
+ ssize_t sent = sendto(sock, buffer.data(), buffer.size(), 0,
|
|
|
+ (struct sockaddr *) &dest_addr, sizeof(dest_addr));
|
|
|
+ if (sent < 0) {
|
|
|
+ std::cerr << "error232-发送失败: " << strerror(errno) << std::endl;
|
|
|
+ }
|
|
|
+
|
|
|
+ // cv::imshow("Server Video", frame);
|
|
|
+ // if (cv::waitKey(1) == 27)
|
|
|
+ // break;
|
|
|
+ }
|
|
|
+
|
|
|
+ close(sock);
|
|
|
+ cap.release();
|
|
|
+}
|
|
|
+
|
|
|
+int configureSerialPort(int fd) {
|
|
|
+ struct termios tty;
|
|
|
+ memset(&tty, 0, sizeof(tty));
|
|
|
+
|
|
|
+ // if (tcgetattr(fd, &tty) {
|
|
|
+ // std::cerr << "[GPS] 从串口获取属性错误: " << strerror(errno) << std::endl;
|
|
|
+ // return -1;
|
|
|
+ // }
|
|
|
+
|
|
|
+ cfsetospeed(&tty, B115200);
|
|
|
+ cfsetispeed(&tty, B115200);
|
|
|
+
|
|
|
+ tty.c_cflag &= ~PARENB;
|
|
|
+ tty.c_cflag &= ~CSTOPB;
|
|
|
+ tty.c_cflag &= ~CSIZE;
|
|
|
+ tty.c_cflag |= CS8;
|
|
|
+ tty.c_cflag &= ~CRTSCTS;
|
|
|
+ tty.c_cflag |= CREAD | CLOCAL;
|
|
|
+
|
|
|
+ tty.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
|
|
|
+ tty.c_oflag &= ~OPOST;
|
|
|
+
|
|
|
+ tty.c_cc[VMIN] = 1;
|
|
|
+ tty.c_cc[VTIME] = 10;
|
|
|
+
|
|
|
+ if (tcsetattr(fd, TCSANOW, &tty)) {
|
|
|
+ std::cerr << "[GPS] 设置串口属性错误: " << strerror(errno) << std::endl;
|
|
|
+ return -1;
|
|
|
+ }
|
|
|
+
|
|
|
+ return 0;
|
|
|
+}
|
|
|
+
|
|
|
+void gpsDataPublisher(const SimpleConfig &config) {
|
|
|
+
|
|
|
+ if (!config.getDevices().gps.enabled || !config.getNetwork().zmq.enabled) {
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ const auto &gps = config.getDevices().gps;
|
|
|
+ int zmq_port = config.getNetwork().zmq.gps_publish_port;
|
|
|
+
|
|
|
+ zmq::context_t ctx(1);
|
|
|
+ zmq::socket_t publisher(ctx, ZMQ_PUB);
|
|
|
+ publisher.bind("tcp://*:" + std::to_string(zmq_port));
|
|
|
+ // const char *port = "/dev/ttyUSB0";
|
|
|
+ int fd = open(gps.serial_port.c_str(), O_RDWR | O_NOCTTY | O_SYNC);
|
|
|
+ if (fd < 0) {
|
|
|
+ std::cerr << "[GPS] 无法打开串口设备 " << gps.serial_port.c_str() << " 错误: " << strerror(errno) << std::endl;
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ if (configureSerialPort(fd)) {
|
|
|
+ close(fd);
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ std::string buffer;
|
|
|
+ char tempBuffer[256];
|
|
|
+ ssize_t n;
|
|
|
+ GPSData current_gps; // 存储当前完整的GPS数据(位置+速度)
|
|
|
+
|
|
|
+ std::cout << "[GPS] 开始GPS数据采集..." << std::endl;
|
|
|
+
|
|
|
+ while (true) {
|
|
|
+ n = read(fd, tempBuffer, sizeof(tempBuffer));
|
|
|
+ if (n > 0) {
|
|
|
+ buffer.append(tempBuffer, n);
|
|
|
+
|
|
|
+ size_t pos;
|
|
|
+ while ((pos = buffer.find("\r\n")) != std::string::npos) {
|
|
|
+ std::string line = buffer.substr(0, pos);
|
|
|
+ buffer.erase(0, pos + 2);
|
|
|
+
|
|
|
+ if (line.find("$GPGGA") == 0) {
|
|
|
+ parseGPGGA(line, current_gps);
|
|
|
+ } else if (line.find("$GPVTG") == 0) {
|
|
|
+ parseGPVTG(line, current_gps);
|
|
|
+ } else if (line.find("$GPHDT") == 0) {
|
|
|
+ parseGPHDT(line, current_gps); // 解析偏航角
|
|
|
+ }
|
|
|
+
|
|
|
+ // 如果所有数据都已更新,则发送完整数据
|
|
|
+ if (!current_gps.timestamp.empty()) {
|
|
|
+ std::ostringstream oss;
|
|
|
+ oss << std::fixed << std::setprecision(9);
|
|
|
+ oss << "{"
|
|
|
+ << "\"timestamp\":\"" << current_gps.timestamp << "\","
|
|
|
+ << "\"latitude\":" << current_gps.latitude << ","
|
|
|
+ << "\"longitude\":" << current_gps.longitude << ","
|
|
|
+ << "\"altitude\":" << current_gps.altitude << ","
|
|
|
+ << "\"speed_knots\":" << current_gps.speed_knots << ","
|
|
|
+ << "\"speed_ms\":" << current_gps.speed_ms << ","
|
|
|
+ << "\"quality\":" << current_gps.quality << ","
|
|
|
+ << "\"satellites\":" << current_gps.satellites << ","
|
|
|
+ << "\"yaw\":" << current_gps.yaw // 新增偏航角
|
|
|
+ << "}";
|
|
|
+
|
|
|
+ zmq::message_t topic("gps", 3);
|
|
|
+ zmq::message_t data(oss.str().data(), oss.str().size());
|
|
|
+ publisher.send(topic, ZMQ_SNDMORE);
|
|
|
+ publisher.send(data, 0);
|
|
|
+
|
|
|
+ // std::cout << "[LOG347][GPS] 发送完整GPS数据: " << oss.str() << std::endl;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ } else if (n < 0) {
|
|
|
+ std::cerr << "[GPS] 读取串口错误: " << strerror(errno) << std::endl;
|
|
|
+ break;
|
|
|
+ }
|
|
|
+
|
|
|
+ std::this_thread::sleep_for(std::chrono::milliseconds(10)); // 更短的延迟
|
|
|
+ }
|
|
|
+
|
|
|
+ close(fd);
|
|
|
+ std::cout << "[GPS] GPS数据采集结束" << std::endl;
|
|
|
+}
|
|
|
+
|
|
|
+// 寄存器地址定义(根据实际协议调整)
|
|
|
+#define AX 0x34
|
|
|
+// #define GX 0x37
|
|
|
+#define LRoll 0x3D
|
|
|
+#define HRoll 0x3E
|
|
|
+#define LPitch 0x3F
|
|
|
+#define HPitch 0x40
|
|
|
+#define LYaw 0x41
|
|
|
+#define HYaw 0x42
|
|
|
+// #define TEMP 0x?? // 根据实际温度寄存器地址修改
|
|
|
+
|
|
|
+// 数据更新标志
|
|
|
+#define ACC_UPDATE 0x01
|
|
|
+// #define GYRO_UPDATE 0x02
|
|
|
+#define ANGLE_UPDATE 0x04
|
|
|
+// #define TEMP_UPDATE 0x08
|
|
|
+
|
|
|
+uint8_t s_cDataUpdate = 0;
|
|
|
+int16_t sReg[128] = {0}; // 假设最大寄存器地址为127
|
|
|
+
|
|
|
+// CRC16-Modbus 校验计算
|
|
|
+uint16_t crc16_modbus(const uint8_t *data, size_t length) {
|
|
|
+ uint16_t crc = 0xFFFF;
|
|
|
+ for (size_t i = 0; i < length; i++) {
|
|
|
+ crc ^= data[i];
|
|
|
+ for (int j = 0; j < 8; j++) {
|
|
|
+ if (crc & 0x0001) {
|
|
|
+ crc = (crc >> 1) ^ 0xA001;
|
|
|
+ } else {
|
|
|
+ crc >>= 1;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ return crc;
|
|
|
+}
|
|
|
+
|
|
|
+// 打开串口
|
|
|
+int open_serial_port(const std::string &port_str, int baud_rate) {
|
|
|
+ const char *port = port_str.c_str();
|
|
|
+ int fd = open(port, O_RDWR | O_NOCTTY);
|
|
|
+ if (fd == -1) {
|
|
|
+ std::cerr << "Error: Unable to open serial port " << port << std::endl;
|
|
|
+ return -1;
|
|
|
+ }
|
|
|
+
|
|
|
+ struct termios options;
|
|
|
+ tcgetattr(fd, &options);
|
|
|
+ cfsetispeed(&options, baud_rate);
|
|
|
+ cfsetospeed(&options, baud_rate);
|
|
|
+
|
|
|
+ options.c_cflag |= (CLOCAL | CREAD);
|
|
|
+ options.c_cflag &= ~PARENB;
|
|
|
+ options.c_cflag &= ~CSTOPB;
|
|
|
+ options.c_cflag &= ~CSIZE;
|
|
|
+ options.c_cflag |= CS8;
|
|
|
+ options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
|
|
|
+ options.c_oflag &= ~OPOST;
|
|
|
+ options.c_cc[VMIN] = 1;
|
|
|
+ options.c_cc[VTIME] = 10;
|
|
|
+
|
|
|
+ if (tcsetattr(fd, TCSANOW, &options) != 0) {
|
|
|
+ std::cerr << "Error: Failed to set serial port attributes" << std::endl;
|
|
|
+ close(fd);
|
|
|
+ return -1;
|
|
|
+ }
|
|
|
+ return fd;
|
|
|
+}
|
|
|
+
|
|
|
+#include <sys/select.h>
|
|
|
+#include <fcntl.h>
|
|
|
+
|
|
|
+// 读取寄存器数据
|
|
|
+bool read_registers(int fd, uint16_t start_reg, uint16_t num_regs) {
|
|
|
+ tcflush(fd, TCIFLUSH); // 每次读取前清空输入缓冲区
|
|
|
+ uint8_t command[] = {
|
|
|
+ 0x50, 0x03,
|
|
|
+ static_cast<uint8_t>(start_reg >> 8), static_cast<uint8_t>(start_reg & 0xFF),
|
|
|
+ static_cast<uint8_t>(num_regs >> 8), static_cast<uint8_t>(num_regs & 0xFF),
|
|
|
+ 0, 0 // CRC placeholder
|
|
|
+ };
|
|
|
+
|
|
|
+ uint16_t crc = crc16_modbus(command, 6);
|
|
|
+ command[6] = crc & 0xFF;
|
|
|
+ command[7] = crc >> 8;
|
|
|
+
|
|
|
+ if (write(fd, command, 8) != 8) {
|
|
|
+ std::cerr << "Error: Failed to send command" << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ uint8_t response[256];
|
|
|
+ int len = read(fd, response, sizeof(response));
|
|
|
+ if (len < 2) {
|
|
|
+ std::cerr << "Error: Incomplete response" << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 校验CRC
|
|
|
+ crc = crc16_modbus(response, len - 2);
|
|
|
+ if (response[len - 2] != (crc & 0xFF) || response[len - 1] != (crc >> 8)) {
|
|
|
+ std::cerr << "Error: CRC mismatch" << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 解析寄存器数据
|
|
|
+ uint8_t byte_count = response[2];
|
|
|
+ if (byte_count != num_regs * 2) {
|
|
|
+ std::cerr << "Error: Unexpected byte count" << std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+
|
|
|
+ for (int i = 0; i < num_regs; i++) {
|
|
|
+ sReg[start_reg + i] = (response[3 + 2 * i] << 8) | response[4 + 2 * i];
|
|
|
+ }
|
|
|
+
|
|
|
+ // 设置数据更新标志
|
|
|
+ if (start_reg == AX)
|
|
|
+ s_cDataUpdate |= ACC_UPDATE;
|
|
|
+ if (start_reg == LRoll || start_reg == HRoll ||
|
|
|
+ start_reg == LPitch || start_reg == HPitch ||
|
|
|
+ start_reg == LYaw || start_reg == HYaw) {
|
|
|
+ s_cDataUpdate |= ANGLE_UPDATE;
|
|
|
+ }
|
|
|
+ // if (start_reg == TEMP) s_cDataUpdate |= TEMP_UPDATE;
|
|
|
+
|
|
|
+ return true;
|
|
|
+}
|
|
|
+
|
|
|
+// 在文件开头添加
|
|
|
+struct IMUData {
|
|
|
+ double accel_x = 0.0;
|
|
|
+ double accel_y = 0.0;
|
|
|
+ double accel_z = 0.0;
|
|
|
+ // double gyro_x = 0.0;
|
|
|
+ // double gyro_y = 0.0;
|
|
|
+ // double gyro_z = 0.0;
|
|
|
+ double roll = 0.0;
|
|
|
+ double pitch = 0.0;
|
|
|
+ double yaw = 0.0;
|
|
|
+ std::string timestamp;
|
|
|
+};
|
|
|
+
|
|
|
+int imuDataPublisher(const SimpleConfig &config) {
|
|
|
+ if (!config.getDevices().imu.enabled || !config.getNetwork().zmq.enabled) {
|
|
|
+ return 0;
|
|
|
+ }
|
|
|
+
|
|
|
+ const auto &imu = config.getDevices().imu;
|
|
|
+ int zmq_port = config.getNetwork().zmq.imu_publish_port;
|
|
|
+ // 使用配置中的串口参数
|
|
|
+ std::string port = imu.serial_port;
|
|
|
+ // int baud_rate = imu.baud_rate; // todo 读取json数据不可用的问题
|
|
|
+ int polling_rate = imu.polling_rate_hz;
|
|
|
+ zmq::context_t ctx(1);
|
|
|
+ zmq::socket_t publisher(ctx, ZMQ_PUB);
|
|
|
+ publisher.bind("tcp://*:" + std::to_string(zmq_port));
|
|
|
+ // const char *port = "/dev/ttyUSB1";
|
|
|
+ int baud_rate = B115200;
|
|
|
+
|
|
|
+ // 打开串口
|
|
|
+ int fd = open_serial_port(imu.serial_port.c_str(), baud_rate);
|
|
|
+ if (fd == -1) {
|
|
|
+ std::cerr << "[IMU] 无法打开串口设备" << std::endl;
|
|
|
+ return 1;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 初始化IMU
|
|
|
+ printf("[IMU] 初始化IMU...");
|
|
|
+ std::this_thread::sleep_for(std::chrono::milliseconds(500)); // 等待传感器启动
|
|
|
+ tcflush(fd, TCIOFLUSH); // 清空输入输出缓冲区
|
|
|
+ printf("完成\n");
|
|
|
+
|
|
|
+ // 设置采集频率
|
|
|
+ const int target_hz = polling_rate;
|
|
|
+ const std::chrono::milliseconds interval(1000 / target_hz);
|
|
|
+
|
|
|
+ while (true) {
|
|
|
+ auto start = std::chrono::steady_clock::now();
|
|
|
+
|
|
|
+ // 读取加速度、角速度、角度
|
|
|
+ read_registers(fd, AX, 3); // 读取加速度
|
|
|
+ // read_registers(fd, GX, 3); // 读取角速度
|
|
|
+ read_registers(fd, LRoll, 1); // 读取角度(包含高低位)
|
|
|
+ read_registers(fd, HRoll, 1); // 读取角度(包含高低位)
|
|
|
+ read_registers(fd, LPitch, 1); // 读取角度(包含高低位)
|
|
|
+ read_registers(fd, HPitch, 1); // 读取角度(包含高低位)
|
|
|
+ read_registers(fd, LYaw, 1); // 读取角度(包含高低位)
|
|
|
+ read_registers(fd, HYaw, 1); // 读取角度(包含高低位)
|
|
|
+
|
|
|
+ // 数据处理
|
|
|
+ if (s_cDataUpdate) {
|
|
|
+ // 获取当前时间戳
|
|
|
+ auto now = std::chrono::system_clock::now();
|
|
|
+ auto now_ms = std::chrono::time_point_cast<std::chrono::milliseconds>(now);
|
|
|
+ auto epoch = now_ms.time_since_epoch();
|
|
|
+ auto value = std::chrono::duration_cast<std::chrono::milliseconds>(epoch);
|
|
|
+ std::string timestamp = std::to_string(value.count());
|
|
|
+
|
|
|
+ // 准备JSON消息
|
|
|
+ std::ostringstream oss;
|
|
|
+ oss << std::fixed << std::setprecision(9);
|
|
|
+ oss << "{"
|
|
|
+ << "\"timestamp\":\"" << timestamp << "\","
|
|
|
+ << "\"accel_x\":" << sReg[AX] / 32768.0f * 16.0f << ","
|
|
|
+ << "\"accel_y\":" << sReg[AX + 1] / 32768.0f * 16.0f << ","
|
|
|
+ << "\"accel_z\":" << sReg[AX + 2] / 32768.0f * 16.0f << ","
|
|
|
+ // << "\"gyro_x\":" << sReg[GX] / 32768.0f * 2000.0f << ","
|
|
|
+ // << "\"gyro_y\":" << sReg[GX + 1] / 32768.0f * 2000.0f << ","
|
|
|
+ // << "\"gyro_z\":" << sReg[GX + 2] / 32768.0f * 2000.0f << ","
|
|
|
+ << "\"roll\":" << ((int32_t)((sReg[HRoll] << 16) | (uint16_t) sReg[LRoll])) / 1000.0f << ","
|
|
|
+ << "\"pitch\":" << ((int32_t)((sReg[HPitch] << 16) | (uint16_t) sReg[LPitch])) / 1000.0f << ","
|
|
|
+ << "\"yaw\":" << ((int32_t)((sReg[HYaw] << 16) | (uint16_t) sReg[LYaw])) / 1000.0f
|
|
|
+ << "}";
|
|
|
+
|
|
|
+ std::string jsonStr = oss.str();
|
|
|
+
|
|
|
+ // 创建并发送ZMQ消息
|
|
|
+ zmq::message_t topic("imu", 3);
|
|
|
+ zmq::message_t data(jsonStr.data(), jsonStr.size());
|
|
|
+
|
|
|
+ try {
|
|
|
+ publisher.send(topic, ZMQ_SNDMORE);
|
|
|
+ publisher.send(data, 0);
|
|
|
+ // std::cout << "[LOG585][IMU] 发送数据: " << jsonStr << std::endl;
|
|
|
+ }
|
|
|
+ catch (const zmq::error_t &e) {
|
|
|
+ std::cerr << "[IMU] ZMQ发送错误: " << e.what() << std::endl;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 清除更新标志
|
|
|
+ s_cDataUpdate = 0;
|
|
|
+ }
|
|
|
+
|
|
|
+ // 频率控制
|
|
|
+ auto end = std::chrono::steady_clock::now();
|
|
|
+ auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(end - start);
|
|
|
+ if (elapsed < interval) {
|
|
|
+ std::this_thread::sleep_for(interval - elapsed);
|
|
|
+ } else {
|
|
|
+ std::cerr << "[IMU] 警告: 循环速度低于" << target_hz << "Hz ("
|
|
|
+ << elapsed.count() << "ms)" << std::endl;
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ close(fd);
|
|
|
+ return 0;
|
|
|
+}
|
|
|
+
|
|
|
+struct SensorFusionData {
|
|
|
+ // GPS数据
|
|
|
+ std::string gps_timestamp;//gps时间
|
|
|
+ double latitude;// 纬度
|
|
|
+ double longitude;// 经度
|
|
|
+ double altitude;// 海拔
|
|
|
+ double speed_knots;// 速度(节)
|
|
|
+ double speed_ms; // 速度(米/秒)
|
|
|
+ int quality; // 定位质量
|
|
|
+ int satellites; // 卫星数量
|
|
|
+ double gps_yaw; // 偏航角(0~359.9°,真北方向)
|
|
|
+
|
|
|
+ // IMU数据
|
|
|
+ std::string imu_timestamp;//imu 时间
|
|
|
+ double accel_x; //x轴加速度
|
|
|
+ double accel_y; //y轴加速度
|
|
|
+ double accel_z; //z轴加速度
|
|
|
+ double roll; //滚转角
|
|
|
+ double pitch; //俯仰角
|
|
|
+ double yaw; //偏航角
|
|
|
+ std::string system_timestamp; // 添加系统时间戳
|
|
|
+};
|
|
|
+
|
|
|
+void updateIMUData(const std::string &jsonStr, SensorFusionData &fusedData) {
|
|
|
+ // 解析JSON并更新IMU数据
|
|
|
+ try {
|
|
|
+ auto j = nlohmann::json::parse(jsonStr);
|
|
|
+ fusedData.accel_x = j["accel_x"];
|
|
|
+ fusedData.accel_y = j["accel_y"];
|
|
|
+ fusedData.accel_z = j["accel_z"];
|
|
|
+ fusedData.roll = j["roll"];
|
|
|
+ fusedData.pitch = j["pitch"];
|
|
|
+ fusedData.yaw = j["yaw"];
|
|
|
+ fusedData.imu_timestamp = j["timestamp"];
|
|
|
+ }
|
|
|
+ catch (...) {
|
|
|
+ std::cerr << "Failed to parse IMU data" << std::endl;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+void updateGPSData(const std::string &jsonStr, SensorFusionData &fusedData) {
|
|
|
+ // 解析JSON并更新GPS数据
|
|
|
+ try {
|
|
|
+ auto j = nlohmann::json::parse(jsonStr);
|
|
|
+ fusedData.gps_timestamp = j["timestamp"];
|
|
|
+ fusedData.latitude = j["latitude"];
|
|
|
+ fusedData.longitude = j["longitude"];
|
|
|
+ fusedData.altitude = j["altitude"];
|
|
|
+ fusedData.speed_knots = j["speed_knots"];
|
|
|
+ fusedData.speed_ms = j["speed_ms"];
|
|
|
+ fusedData.quality = j["quality"];
|
|
|
+ fusedData.satellites = j["satellites"];
|
|
|
+ fusedData.gps_yaw = j["yaw"];
|
|
|
+ }
|
|
|
+ catch (...) {
|
|
|
+ std::cerr << "Failed to parse GPS data" << std::endl;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+void publishFusedData(zmq::socket_t &publisher, const SensorFusionData &data) {
|
|
|
+ std::ostringstream oss;
|
|
|
+ oss << std::fixed << std::setprecision(9);
|
|
|
+ oss << "{"
|
|
|
+ << "\"system_timestamp\":\"" << data.system_timestamp << "\"," // 添加系统时间戳
|
|
|
+ << "\"gps_timestamp\":\"" << data.gps_timestamp << "\","
|
|
|
+ << "\"imu_timestamp\":\"" << data.imu_timestamp << "\","
|
|
|
+ << "\"latitude\":" << data.latitude << ","
|
|
|
+ << "\"longitude\":" << data.longitude << ","
|
|
|
+ << "\"altitude\":" << data.altitude << ","
|
|
|
+ << "\"speed_knots\":" << data.speed_knots << ","
|
|
|
+ << "\"speed_ms\":" << data.speed_ms << ","
|
|
|
+ << "\"quality\":" << data.quality << ","
|
|
|
+ << "\"satellites\":" << data.satellites << ","
|
|
|
+ << "\"gps_yaw\":" << data.gps_yaw << ","
|
|
|
+ << "\"accel_x\":" << data.accel_x << ","
|
|
|
+ << "\"accel_y\":" << data.accel_y << ","
|
|
|
+ << "\"accel_z\":" << data.accel_z << ","
|
|
|
+ << "\"roll\":" << data.roll << ","
|
|
|
+ << "\"pitch\":" << data.pitch << ","
|
|
|
+ << "\"yaw\":" << data.yaw
|
|
|
+ << "}";
|
|
|
+
|
|
|
+ std::string jsonStr = oss.str();
|
|
|
+ zmq::message_t topic("fused", 5);
|
|
|
+ zmq::message_t data_msg(jsonStr.data(), jsonStr.size());
|
|
|
+ publisher.send(topic, ZMQ_SNDMORE);
|
|
|
+ publisher.send(data_msg, 0);
|
|
|
+ std::cout << "[LOG697][IMU GPS] 发送数据: " << jsonStr << std::endl;
|
|
|
+}
|
|
|
+
|
|
|
+void fusedDataPublisher(const SimpleConfig &config) {
|
|
|
+ if (!config.getNetwork().zmq.enabled) {
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ zmq::context_t ctx(1);
|
|
|
+ zmq::socket_t publisher(ctx, ZMQ_PUB);
|
|
|
+ int zmq_port = config.getNetwork().zmq.fused_publish_port;
|
|
|
+ publisher.bind("tcp://*:" + std::to_string(zmq_port));
|
|
|
+
|
|
|
+ zmq::socket_t subscriber(ctx, ZMQ_SUB);
|
|
|
+ subscriber.connect("tcp://localhost:" + std::to_string(config.getNetwork().zmq.imu_publish_port));
|
|
|
+ subscriber.connect("tcp://localhost:" + std::to_string(config.getNetwork().zmq.gps_publish_port));
|
|
|
+ subscriber.setsockopt(ZMQ_SUBSCRIBE, "", 0); // 订阅所有消息
|
|
|
+
|
|
|
+ SensorFusionData fusedData;
|
|
|
+ auto lastUpdate = std::chrono::system_clock::now();
|
|
|
+
|
|
|
+ while (true) {
|
|
|
+ zmq::message_t topic;
|
|
|
+ zmq::message_t data;
|
|
|
+
|
|
|
+ // 接收主题
|
|
|
+ if (subscriber.recv(&topic)) {
|
|
|
+ // 接收数据
|
|
|
+ if (subscriber.recv(&data)) {
|
|
|
+ std::string topic_str(static_cast<char *>(topic.data()), topic.size());
|
|
|
+ std::string data_str(static_cast<char *>(data.data()), data.size());
|
|
|
+
|
|
|
+ try {
|
|
|
+ if (topic_str == "imu") {
|
|
|
+ updateIMUData(data_str, fusedData);
|
|
|
+ } else if (topic_str == "gps") {
|
|
|
+ updateGPSData(data_str, fusedData);
|
|
|
+ }
|
|
|
+
|
|
|
+ // 添加系统时间戳
|
|
|
+ auto now = std::chrono::system_clock::now();
|
|
|
+ auto duration = now.time_since_epoch();
|
|
|
+ auto millis = std::chrono::duration_cast<std::chrono::milliseconds>(duration).count();
|
|
|
+ fusedData.system_timestamp = std::to_string(millis);
|
|
|
+
|
|
|
+ // 控制发布频率
|
|
|
+ if (std::chrono::duration_cast<std::chrono::milliseconds>(
|
|
|
+ now - lastUpdate).count() >= 40) { // 默认50ms
|
|
|
+ publishFusedData(publisher, fusedData);
|
|
|
+ lastUpdate = now;
|
|
|
+ }
|
|
|
+ } catch (const std::exception &e) {
|
|
|
+ std::cerr << "[FUSED] 数据处理错误: " << e.what() << std::endl;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+int main() {
|
|
|
+ SimpleConfig config;
|
|
|
+ if (!config.load("../config-release.json")) {
|
|
|
+ return 1;
|
|
|
+ }
|
|
|
+
|
|
|
+ try {
|
|
|
+ std::cout << "[MAIN] 服务器启动..." << std::endl;
|
|
|
+
|
|
|
+ std::vector <std::thread> threads; // 只保留这一个声明
|
|
|
+
|
|
|
+ // 1. 视频流线程(独立)
|
|
|
+ if (config.getNetwork().udp.enabled && config.getDevices().camera.enabled) {
|
|
|
+ threads.emplace_back(videoStreamUDP, std::ref(config));
|
|
|
+ }
|
|
|
+
|
|
|
+ // 2. 启动传感器数据采集和原始发布线程
|
|
|
+ if (config.getNetwork().zmq.enabled) {
|
|
|
+ // IMU原始数据发布
|
|
|
+ if (config.getDevices().imu.enabled) {
|
|
|
+ threads.emplace_back(imuDataPublisher, std::ref(config));
|
|
|
+ std::this_thread::sleep_for(std::chrono::milliseconds(50)); // 稍等确保绑定完成
|
|
|
+ }
|
|
|
+
|
|
|
+ // GPS原始数据发布
|
|
|
+ if (config.getDevices().gps.enabled) {
|
|
|
+ threads.emplace_back(gpsDataPublisher, std::ref(config));
|
|
|
+ std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
|
|
+ }
|
|
|
+
|
|
|
+ // 3. 融合数据发布线程(订阅上述原始数据)
|
|
|
+ threads.emplace_back(fusedDataPublisher, std::ref(config));
|
|
|
+ }
|
|
|
+
|
|
|
+ // 等待所有线程完成
|
|
|
+ for (auto &t: threads) {
|
|
|
+ if (t.joinable()) {
|
|
|
+ t.join();
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ } catch (const std::exception &e) {
|
|
|
+ std::cerr << "[MAIN] 错误: " << e.what() << std::endl;
|
|
|
+ return 1;
|
|
|
+ }
|
|
|
+ return 0;
|
|
|
+}
|