串口相关类

SerialParity.h

enum class SerialParity : char {
    None = 'N',
    Odd = 'O',
    Even = 'E'
};

SerialPortConfig.h

// 串口配置结构体
struct SerialPortConfig {
    std::string port ;           // 串口号
    int baud_rate = 9600;        // 波特率
    char data_bits = 8;          // 数据位 (5,6,7,8)
    char stop_bits = 1;          // 停止位 (1,2)
    SerialParity parity = SerialParity::None;           // 校验位 (N:无校验, E:偶校验, O:奇校验)
    bool flow_control = false;   // 流控
    int timeout_ms = 100;        // 超时时间(毫秒)
};

SerialPort.h

//
// Created by HP on 2025/8/6.
//

#ifndef SIFANG103_SERIALPORT_H
#define SIFANG103_SERIALPORT_H


#include <iostream>
#include <string>
#include <stdexcept>
#include <fcntl.h>
#include <unistd.h>
#include <termios.h>
#include <system_error>
#include <cstring>
#include <vector>
#include <thread>
#include <atomic>
#include <mutex>
#include <condition_variable>
#include <functional>

#include "SerialPortConfig.h"


class SerialPort {
public:
    explicit SerialPort(const SerialPortConfig &config = {})
            : port_(config.port), config_(config) {

        open();

        if (!initSerialPort()) {
            throw std::runtime_error("Failed to open serial port: " + port_ +
                                     " Error: " + std::strerror(errno));
        }
    }

    ~SerialPort() {
        close();
    }

    // 打开串口
    void open();

    // 关闭串口
    void close();

    // 检查串口是否打开
    [[nodiscard]] bool isOpen() const {
        return fd_ >= 0;
    }

    // 发送数据
    void send(const std::vector<uint8_t> &data) const;

    void send(const uint8_t *data, size_t size) const;

    // 接收数据 (阻塞方式)
    [[nodiscard]] std::vector<uint8_t> receive(size_t max_size = 1024) const;

    // 开始监听串口数据 (异步方式)
    void startListening();

    // 停止监听
    void stopListening();

    // 设置数据接收回调
    void setDataCallback(std::function<void(const std::vector<uint8_t> &)> callback);

    // 获取串口名称
    [[nodiscard]] const std::string &port() const;

    // 初始化串口操作
    [[nodiscard]] bool initSerialPort() const;

private:
    // 配置串口参数
    void configure() const;

    // 监听线程
    void listenerThread();

    // 防止粘包处理函数
    /// @param uint64_t 已经存入的数据长度
    /// @param uint64_t 尚未存入的数据长度
    /// @param std::vector<uint8_t> 已经按照数据长度开辟的vector<uint8_t>数组
    [[nodiscard]] std::tuple<uint64_t, uint64_t, std::vector<uint8_t> > handleStickyPackets();

    std::string port_;              /* 串口号 */
    SerialPortConfig config_;       /* 串口相关配置 */
    int fd_ = -1l;                  /* 串口文件描述符 */

    // 监听相关成员
    std::atomic<bool> running_{false};
    std::thread listener_thread_;

    // 回调函数
    std::function<void(const std::vector<uint8_t> &)> data_callback_;
    std::function<void(const std::error_code &)> error_callback_;

    // 互斥锁
    std::mutex callback_mutex_;
};


#endif //SIFANG103_SERIALPORT_H

SerialPort.cpp

//
// Created by HP on 2025/8/6.
//

#include <iomanip>
#include "SerialPort.h"

#include "../../GlobalVariable/GlobalMessageMonitor.h"
#include "../../GlobalVariable/GlobalConfigureReader.h"
#include "../../ToolUtils/DataValidator.h"
#include "../../GlobalVariable/GlobalRunningFlag.h"

//#define DEBUG

void SerialPort::open() {

    if (isOpen()) {
        throw std::runtime_error("Serial port already open");
    }

    // 以读写和非阻塞方式打开串口
    // O_EXCL 创建文件时,如果文件已经存在,则返回错误
    fd_ = ::open(port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK | O_EXCL);
    if (fd_ < 0) {
        throw std::system_error(errno, std::system_category(), "Failed to open serial port " + port_);
    }

    try {
        configure();
    } catch (...) {
        ::close(fd_);
        fd_ = -1;
        throw;
    }
}

void SerialPort::close() {
    stopListening();
    if (isOpen()) {
        ::close(fd_);
        fd_ = -1;
    }
}


void SerialPort::send(const std::vector<uint8_t> &data) const {

    if (data.empty()) {
        throw std::runtime_error("Send data is empty.");
    }

    send(data.data(), data.size());
#ifdef DEBUG
    /* 发送帧输出 */
    std::cout << "Send: " << std::hex;
    for (const auto &charc: data) {
        std::cout << std::hex << std::setw(2) << std::setfill('0') << static_cast<int>(charc) << " ";
    }
    std::cout << std::endl;
#endif
    /* 推送发送报文 */
    GlobalMessageMonitor::messageMonitor->pushSendData(const_cast<std::vector<uint8_t> &>(data));
}

void SerialPort::send(const uint8_t *data, size_t size) const {

    try {
        if (!isOpen()) {
            throw std::runtime_error("Serial port not open");
        }

        ssize_t written = ::write(fd_, data, size);
        if (written < 0) {
            throw std::system_error(errno, std::system_category(),
                                    "Failed to write to serial port");
        }

        if (static_cast<size_t>(written) != size) {
            throw std::runtime_error("Incomplete write to serial port");
        }
    } catch (const std::exception &e) {
        std::cout << "Serial Port : send error." << std::endl;
    }


}

std::vector<uint8_t> SerialPort::receive(size_t max_size) const {
    if (!isOpen()) {
        throw std::runtime_error("Serial port not open");
    }

    std::vector<uint8_t> buffer(max_size);
    ssize_t n = ::read(fd_, buffer.data(), max_size);

    if (n < 0) {
        if (errno == EAGAIN || errno == EWOULDBLOCK) {
            return {}; // 没有数据
        }
        throw std::system_error(errno, std::system_category(),
                                "Failed to read from serial port");
    }

    buffer.resize(n);
    return buffer;
}

void SerialPort::startListening() {

    if (!isOpen()) {
        throw std::runtime_error("Serial port not open");
    }

    if (running_) return;

    running_ = true;
    listener_thread_ = std::thread(&SerialPort::listenerThread, this);
}

void SerialPort::stopListening() {
    if (!running_) return;

    running_ = false;
    if (listener_thread_.joinable()) {
        listener_thread_.join();
    }
}

void SerialPort::setDataCallback(std::function<void(const std::vector<uint8_t> &)> callback) {
    std::lock_guard<std::mutex> lock(callback_mutex_);
    data_callback_ = std::move(callback);
}

const std::string &SerialPort::port() const {
    return port_;
}

void SerialPort::configure() const {

    struct termios tty{};
    memset(&tty, 0, sizeof(tty));

    // 获取当前配置
    if (tcgetattr(fd_, &tty) != 0) {
        throw std::system_error(errno, std::system_category(), "tcgetattr failed");
    }

    // 设置输入输出波特率
    cfsetispeed(&tty, config_.baud_rate);
    cfsetospeed(&tty, config_.baud_rate);

    // 设置数据位
    tty.c_cflag &= ~CSIZE;
    switch (config_.data_bits) {
        case 5:
            tty.c_cflag |= CS5;
            break;
        case 6:
            tty.c_cflag |= CS6;
            break;
        case 7:
            tty.c_cflag |= CS7;
            break;
        case 8:
            tty.c_cflag |= CS8;
            break;
        default:
            throw std::runtime_error("Invalid data bits");
    }

    // 设置停止位
    if (config_.stop_bits == 2) {
        tty.c_cflag |= CSTOPB;
    } else if (config_.stop_bits == 1) {
        tty.c_cflag &= ~CSTOPB;
    } else {
        throw std::runtime_error("Invalid stop bits");
    }

    // 设置校验位
    switch (config_.parity) {
        case SerialParity::None: // 无校验
            tty.c_cflag &= ~PARENB;
            break;
        case SerialParity::Odd: // 偶校验
            tty.c_cflag |= PARENB;
            tty.c_cflag &= ~PARODD;
            break;
        case SerialParity::Even: // 奇校验
            tty.c_cflag |= PARENB;
            tty.c_cflag |= PARODD;
            break;
        default:
            throw std::runtime_error("Invalid parity");
    }

    // 设置流控
    if (config_.flow_control) {
        tty.c_cflag |= CRTSCTS;
    } else {
        tty.c_cflag &= ~CRTSCTS;
    }

    // 其他设置
    tty.c_cflag |= (CLOCAL | CREAD); // 本地连接,启用接收
    tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP
                     | INLCR | IGNCR | ICRNL | IXON);
    tty.c_lflag &= ~ICANON;          // 非规范模式
    tty.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN); // 禁用回显和信号
    tty.c_oflag &= ~OPOST;           // 原始输出
    tty.c_oflag &= ~ONLCR;           // 禁止将换行符转换为回车换行符

    /*使用原始模式(Raw Mode)方式来通讯*/

    ///@see https://www.man7.org/linux/man-pages/man3/cfmakeraw.3.html
//    cfmakeraw(&tty);          /*  Version 7 api */
//    此行代码与下面代码行等价
//    tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP
//                     | INLCR | IGNCR | ICRNL | IXON);
//    tty.c_oflag &= ~OPOST;
//    tty.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
//    tty.c_cflag &= ~(CSIZE | PARENB);
//    tty.c_cflag |= CS8;

    // 设置超时
    tty.c_cc[VTIME] = config_.timeout_ms / 100;
    tty.c_cc[VMIN] = 0; // 非阻塞读取

    // 应用配置
    if (tcsetattr(fd_, TCSANOW, &tty) != 0) {
        throw std::system_error(errno, std::system_category(), "tcsetattr failed");
    }
}

void SerialPort::listenerThread() {


    while (running_ && GlobalRunningFlag::isRunning) {

        auto res = handleStickyPackets();

        auto recvSize = std::get<0>(res);

        std::vector<uint8_t> buffer = std::get<2>(res);

        /* 阻塞等待后续数据 */
        while (recvSize < std::get<1>(res)) {

            /* 尝试读取剩余的字节 */
            auto n = ::read(fd_, buffer.data() + recvSize, std::get<2>(res).size() - recvSize);

            if (n > 0) {
                recvSize += n;
            } else if (n < 0 && errno != EAGAIN) {
                // 错误处理
                std::lock_guard<std::mutex> lock(callback_mutex_);
                if (error_callback_) {
                    error_callback_(std::make_error_code(static_cast<std::errc>(errno)));
                }
            }
        }

        /* 检查输入std::vector<uint8_t> 按照结束字符进行截取防止粘包 */
        buffer = DataValidator::dataFormatter(buffer);


        std::lock_guard<std::mutex> lock(callback_mutex_);
        if (data_callback_) {
            data_callback_(buffer);
        }


        // 短暂休眠以减少CPU占用 过快读取会导致串口数据接收不全 过慢会导致粘包
        std::this_thread::sleep_for(
                std::chrono::milliseconds(GlobalConfigureReader::configureReader->getReceiveInterval()));


    }

}

bool SerialPort::initSerialPort() const {

    struct termios tty{};
    if (tcgetattr(fd_, &tty) != 0) {
        throw std::system_error(errno, std::system_category(), "tcgetattr failed");
    }

    // 1. 设置输入输出波特率为 9600
    cfsetispeed(&tty, B9600);
    cfsetospeed(&tty, B9600);
    cfmakeraw(&tty);
    // 2. 控制模式 (Control Modes)
    tty.c_cflag &= ~PARENB;  // 禁用奇偶校验生成和检测
    tty.c_cflag &= ~CSTOPB;  // 设置 1 个停止位 (清除 CSTOPB 意味着 1 位)
    tty.c_cflag &= ~CSIZE;   // 先清除数据位掩码
    tty.c_cflag |= CS8;      // 设置数据位为 8 位
    tty.c_cflag &= ~CRTSCTS; // 禁用硬件流控 (RTS/CTS)
    tty.c_cflag |= CREAD | CLOCAL; // 开启接收器,忽略调制解调器控制线

    // 3. 本地模式 (Local Modes)
    tty.c_lflag &= ~ICANON;  // 禁用规范模式(行缓冲、特殊字符处理)
    tty.c_lflag &= ~ECHO;    // 禁用回显
    tty.c_lflag &= ~ECHOE;   // 禁用擦除字符的回显
    tty.c_lflag &= ~ECHONL;  // 禁用换行符的回显
    tty.c_lflag &= ~ISIG;    // 禁用对 INTR, QUIT, SUSP 等信号字符的处理

    // 4. 输入模式 (Input Modes)
    tty.c_iflag &= ~(IXON | IXOFF | IXANY); // 禁用软件流控 (XON/XOFF)
    tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL);

    // 5. 输出模式 (Output Modes)
    tty.c_oflag &= ~OPOST; // 禁用输出处理,使用原始输出(不映射换行符等)
    tty.c_oflag &= ~ONLCR;

    // 6. 特殊字符和控制参数
    // 设置超时和最小读取字符数
    tty.c_cc[VTIME] = 10; // 等待数据的十分之几秒 (Inter-character timer)
    tty.c_cc[VMIN] = 0;   // 读取所需的最小字符数 (Blocking read until 1 character arrives)
    // VMIN=0, VTIME=10: 读请求最多等待1秒,即使没读到任何数据也返回
    // VMIN=1, VTIME=10: 读请求会一直阻塞,直到至少收到1个字符,之后如果字符间隔超过1秒则返回

    // 7. 清空输入输出缓冲区,丢弃任何未读的数据或未发送的数据
    tcflush(fd_, TCIOFLUSH);

    // 8. 将新的属性立即应用于串口
    if (tcsetattr(fd_, TCSANOW, &tty) != 0) {
        printf("Error setting terminal attributes: %s\n", strerror(errno));
        ::close(fd_);
        return false;
    }
    return true;
}

std::tuple<uint64_t, uint64_t, std::vector<uint8_t> > SerialPort::handleStickyPackets() {


    while (running_) {

        uint8_t firstCharacter{};

        ssize_t n = ::read(fd_, &firstCharacter, 1);

        if (n == -1) {
            continue;
        }

        if (n < 0 && errno != EAGAIN && errno != EWOULDBLOCK) {
            // 错误处理
            std::lock_guard<std::mutex> lock(callback_mutex_);
            if (error_callback_) {
                error_callback_(std::make_error_code(static_cast<std::errc>(errno)));
            }
        }

        /* 判断固定帧还是短帧 */
        if (firstCharacter == 0x10) {

            /* 读取剩余的4个字符 */
            std::vector<uint8_t> buffer{firstCharacter};
            /* 为后续数据留好空间 */
            buffer.resize(5l);
            return {1l, 4l, buffer};

        } else if (firstCharacter == 0x68) {


            std::vector<uint8_t> buffer{firstCharacter};

            constexpr size_t dataHeaderLength = 4;          /* 读取开头的4个字符 */
            buffer.resize(dataHeaderLength);

            uint64_t index{1};                               /* 记录当前已经读取的字节数 */

            /* 读取完整的数据头 数据不足时阻塞读取 */
            while (index < 4) {
                /* 只需要再读取3个字符 即可组成头 */
                n = ::read(fd_, buffer.data() + 1l, 3);
                if (n > 0) {
                    index += n; /* 累加新接收到的字符 */
                }
            }

            /* 为后续数据留好空间 */
            buffer.resize(buffer.at(1) + 6l);
            return {index, buffer.size() - index, buffer};

        } else {
            // 收到异常帧 丢弃处理
            continue;
        }
    }

    /* 退出循环返回空 */
    return {0, 0, {}};
}

posted @ 2025-10-09 13:56  BlackSnow  阅读(4)  评论(0)    收藏  举报