/** * @file SerialPortUnixBase.h * @author itas109 (itas109@qq.com) \n\n * Blog : https://blog.csdn.net/itas109 \n * Github : https://github.com/itas109 \n * QQ Group : 12951803 * @brief the CSerialPort unix Base class unix串口基类 * @date 2020-04-29 * @copyright The CSerialPort is Copyright (C) 2021 itas109. \n * Contact: itas109@qq.com \n\n * You may use, distribute and copy the CSerialPort under the terms of \n * GNU Lesser General Public License version 3, which is displayed below. */ #ifndef __CSERIALPORTUNIXBASE_H__ #define __CSERIALPORTUNIXBASE_H__ #include "SerialPortBase.h" #include /* Error number definitions */ #include /* File control definitions */ #include /* Standard input/output definitions */ #include /* String function definitions */ #include /* POSIX terminal control definitions */ #include /* UNIX standard function definitions */ #include //ioctl // Serial Programming Guide for POSIX Operating Systems // https://digilander.libero.it/robang/rubrica/serial.htm // https://blog.csdn.net/u014650722/article/details/51610587 // sigslot // https://sourceforge.net/p/sigslot/bugs/8/ #include "sigslot.h" // https://blog.csdn.net/u010317005/article/details/52384890 // Linux compile 1 // g++ SerialPort.cpp SerialPortBase.cpp SerialPortUnixBase.cpp -fPIC -lpthread -shared -o libsp.so // g++ t.cpp -o sp -L. -lsp // export LD_LIBRARY_PATH=./ // ./sp // Linux compile 2 // g++ sp.cpp SerialPort.cpp SerialPortBase.cpp SerialPortUnixBase.cpp -lpthread -o sp // ./sp // sp.cpp /* #include #include "SerialPort.h" #include "sigslot.h" using namespace itas109; using namespace std; int main() { CSerialPort sp; sp.init("/dev/ttyS0"); sp.open(); cout << sp.isOpened() <= 0)//非阻塞,覆盖前面open的属性 if (fcntl(fd, F_SETFL, 0) >= 0) // 阻塞,即使前面在open串口设备时设置的是非阻塞的,这里设为阻塞后,以此为准 { // set param if (uart_set(fd, m_baudRate, m_parity, m_dataBits, m_stopbits, m_flowControl) == -1) { fprintf(stderr, "uart set failed!\n"); // exit(EXIT_FAILURE); bRet = false; lastError = itas109::/*SerialPortError::*/ InvalidParameterError; } else { m_isThreadRunning = true; bRet = startThreadMonitor(); if (!bRet) { m_isThreadRunning = false; lastError = itas109::/*SerialPortError::*/ SystemError; } } } else { bRet = false; lastError = itas109::/*SerialPortError::*/ SystemError; } } else { // Could not open the port char str[256]; snprintf(str, sizeof(str), "open port error: Unable to open %s", m_portName.c_str()); perror(str); bRet = false; lastError = itas109::/*SerialPortError::*/ OpenError; } if (!bRet) { closePort(); } unlock(); return bRet; } /** * @brief close 关闭串口 * */ virtual void closePort(){ if (isOpened()) { stopThreadMonitor(); close(fd); fd = -1; } } /** * @brief if serial port is open success 串口是否打开成功 * * @return * @retval true serial port open success 串口打开成功 * @retval false serial port open failed 串口打开失败 */ virtual bool isOpened(){ return fd != -1; } /** * @brief read specified length data 读取指定长度数据 * * @param data [out] read data result 读取结果 * @param maxSize [in] read length 读取长度 * @return return number Of bytes read 返回读取字节数 * @retval -1 read error 读取错误 * @retval [other] return number Of bytes read 返回读取字节数 */ virtual int readData(char *data, int maxSize){ int iRet = -1; lock(); if (isOpened()) { iRet = read(fd, data, maxSize); } else { lastError = itas109::/*SerialPortError::*/ NotOpenError; iRet = -1; } unlock(); return iRet; } /** * @brief read all data 读取所有数据 * * @param data [out] read data result 读取结果 * @return return number Of bytes read 返回读取字节数 * @retval -1 read error 读取错误 * @retval [other] return number Of bytes read 返回读取字节数 */ virtual int readAllData(char *data){ int readbytes = 0; // read前获取可读的字节数,不区分阻塞和非阻塞 ioctl(fd, FIONREAD, &readbytes); return readData(data, readbytes); } /** * @brief read line data 读取一行字符串 * @todo Not implemented 未实现 * * @param data * @param maxSize * @return int */ virtual int readLineData(char *data, int maxSize){ int iRet = -1; lock(); if (isOpened()) { } else { lastError = itas109::/*SerialPortError::*/ NotOpenError; iRet = -1; } unlock(); return iRet; } /** * @brief write specified lenfth data 写入指定长度数据 * * @param data [in] write data 待写入数据 * @param maxSize [in] wtite length 写入长度 * @return return number Of bytes write 返回写入字节数 * @retval -1 read error 写入错误 * @retval [other] return number Of bytes write 返回写入字节数 */ virtual int writeData(const char *data, int maxSize){ int iRet = -1; // lock(); if (isOpened()) { // Write N bytes of BUF to FD. Return the number written, or -1 iRet = write(fd, data, maxSize); } else { lastError = itas109::/*SerialPortError::*/ NotOpenError; iRet = -1; } // unlock(); return iRet; } /** * @brief Set Debug Model 设置调试模式 * @details output serial port read and write details info 输出串口读写的详细信息 * @todo Not implemented 未实现 * * @param isDebug true if enable true为启用 */ virtual void setDebugModel(bool isDebug){ } /** * @brief Set the Read Time Interval object * @details use timer import effectiveness 使用定时器提高效率 * @todo Not implemented 未实现 * * @param msecs read time micro second 读取间隔时间,单位:毫秒 */ virtual void setReadTimeInterval(int msecs){ } /** * @brief setMinByteReadNotify set minimum byte of read notify 设置读取通知触发最小字节数 * @param minByteReadNotify minimum byte of read notify 读取通知触发最小字节数 */ virtual void setMinByteReadNotify(unsigned int minByteReadNotify = 2){ m_minByteReadNotify = minByteReadNotify; } /** * @brief Get the Last Error object 获取最后的错误代码 * * @return return last error code, refrence {@link itas109::SerialPortError} 错误代码 */ virtual int getLastError() const{ return lastError; } /** * @brief clear error 清除错误信息 * */ virtual void clearError(){ lastError = itas109::NoError; } /** * @brief Set the Port Name object 设置串口名称 * * @param portName [in] the port name 串口名称 Windows:COM1 Linux:/dev/ttyS0 */ virtual void setPortName(std::string portName){ m_portName = portName; } /** * @brief Get the Port Name object 获取串口名称 * * @return return port name 返回串口名称 */ virtual std::string getPortName() const{ return m_portName; } /** * @brief Set the Baud Rate object 设置波特率 * * @param baudRate [in] the baudRate 波特率 */ virtual void setBaudRate(int baudRate){ m_baudRate = baudRate; } /** * @brief Get the Baud Rate object 获取波特率 * * @return return baudRate 返回波特率 */ virtual int getBaudRate() const{ return m_baudRate; } /** * @brief Set the Parity object 设置校验位 * * @param parity [in] the parity 校验位 {@link itas109::Parity} */ virtual void setParity(itas109::Parity parity){ m_parity = parity; } /** * @brief Get the Parity object 获取校验位 * * @return return parity 返回校验位 {@link itas109::Parity} */ virtual itas109::Parity getParity() const{ return m_parity; } /** * @brief Set the Data Bits object 设置数据位 * * @param dataBits [in] the dataBits 数据位 {@link itas109::DataBits} */ virtual void setDataBits(itas109::DataBits dataBits){ m_dataBits = dataBits; } /** * @brief Get the Data Bits object 获取数据位 * * @return return dataBits 返回数据位 {@link itas109::DataBits} */ virtual itas109::DataBits getDataBits() const{ return m_dataBits; } /** * @brief Set the Stop Bits object 设置停止位 * * @param stopbits [in] the stopbits 停止位 {@link itas109::StopBits} */ virtual void setStopBits(itas109::StopBits stopbits){ m_stopbits = stopbits; } /** * @brief Get the Stop Bits object 获取停止位 * * @return return stopbits 返回停止位 {@link itas109::StopBits} */ virtual itas109::StopBits getStopBits() const{ return m_stopbits; } /** * @brief Set the Flow Control object 设置流控制 * @todo Not implemented 未实现 * * @param flowControl [in] */ virtual void setFlowControl(itas109::FlowControl flowControl){ m_flowControl = flowControl; } /** * @brief Get the Flow Control object 获取流控制 * @todo Not implemented 未实现 * * @return itas109::FlowControl */ virtual itas109::FlowControl getFlowControl() const{ return m_flowControl; } /** * @brief Set the Read Buffer Size object 设置读取缓冲区大小 * * @param size [in] read buffer size 读取缓冲区大小 */ virtual void setReadBufferSize(int64_t size){ m_readBufferSize = size; } /** * @brief Get the Read Buffer Size object 获取读取缓冲区大小 * * @return return read buffer size 返回读取缓冲区大小 */ virtual int64_t getReadBufferSize() const{ return m_readBufferSize; } /** * @brief Set the Dtr object 设置DTR * @todo Not implemented 未实现 * * @param set [in] */ virtual void setDtr(bool set = true){} /** * @brief Set the Rts object 设置RTS * @todo Not implemented 未实现 * * @param set [in] */ virtual void setRts(bool set = true){} /** * @brief Get the Version object 获取版本信息 * * @return return version 返回版本信息 */ std::string getVersion(){ std::string m_version = "CSerialPortUnixBase V1.0.1.190728"; return m_version; } public: /** * @brief isThreadRunning 是否启动多线程 * @return * @retval true thread running 多线程已启动 * @retval false thread not running 多线程未启动 */ bool isThreadRunning(){ return m_isThreadRunning; } private: /** * @brief lock 锁 * */ void lock(){ pthread_mutex_lock(&m_communicationMutex); } /** * @brief unlock 解锁 * */ void unlock(){ pthread_mutex_unlock(&m_communicationMutex); } /** * @brief rate2Constant baudrate to constant 波特率转为unix常量 * @param baudrate 波特率 * @return constant unix常量 */ int rate2Constant(int baudrate){ // https://jim.sh/ftx/files/linux-custom-baudrate.c #define B(x) \ case x: \ return B##x switch (baudrate) { #ifdef B50 B(50); #endif #ifdef B75 B(75); #endif #ifdef B110 B(110); #endif #ifdef B134 B(134); #endif #ifdef B150 B(150); #endif #ifdef B200 B(200); #endif #ifdef B300 B(300); #endif #ifdef B600 B(600); #endif #ifdef B1200 B(1200); #endif #ifdef B1800 B(1800); #endif #ifdef B2400 B(2400); #endif #ifdef B4800 B(4800); #endif #ifdef B9600 B(9600); #endif #ifdef B19200 B(19200); #endif #ifdef B38400 B(38400); #endif #ifdef B57600 B(57600); #endif #ifdef B115200 B(115200); #endif #ifdef B230400 B(230400); #endif #ifdef B460800 B(460800); #endif #ifdef B500000 B(500000); #endif #ifdef B576000 B(576000); #endif #ifdef B921600 B(921600); #endif #ifdef B1000000 B(1000000); #endif #ifdef B1152000 B(1152000); #endif #ifdef B1500000 B(1500000); #endif #ifdef B2000000 B(2000000); #endif #ifdef B2500000 B(2500000); #endif #ifdef B3000000 B(3000000); #endif #ifdef B3500000 B(3500000); #endif #ifdef B4000000 B(4000000); #endif default: return 0; } #undef B } /** * @brief uart_set * @param fd * @param baude * @param c_flow * @param bits * @param parity * @param stop * @return 0 success -1 error */ int uart_set(int fd, int baudRate = itas109::BaudRate9600, itas109::Parity parity = itas109::ParityNone, itas109::DataBits dataBits = itas109::DataBits8, itas109::StopBits stopbits = itas109::StopOne, itas109::FlowControl flowControl = itas109::FlowNone){ struct termios options; //获取终端属性 if (tcgetattr(fd, &options) < 0) { perror("tcgetattr error"); return -1; } //设置输入输出波特率 int baudRateConstant = 0; baudRateConstant = rate2Constant(baudRate); if (0 != baudRateConstant) { cfsetispeed(&options, baudRateConstant); cfsetospeed(&options, baudRateConstant); } else { // TODO: custom baudrate fprintf(stderr, "Unkown baudrate!\n"); return -1; } //设置校验位 switch (parity) { /*无奇偶校验位*/ case itas109::ParityNone: case 'N': options.c_cflag &= ~PARENB; // PARENB:产生奇偶位,执行奇偶校验 options.c_cflag &= ~INPCK; // INPCK:使奇偶校验起作用 break; /*设置奇校验*/ case itas109::ParityOdd: options.c_cflag |= PARENB; // PARENB:产生奇偶位,执行奇偶校验 options.c_cflag |= PARODD; // PARODD:若设置则为奇校验,否则为偶校验 options.c_cflag |= INPCK; // INPCK:使奇偶校验起作用 options.c_cflag |= ISTRIP; // ISTRIP:若设置则有效输入数字被剥离7个字节,否则保留全部8位 break; /*设置偶校验*/ case itas109::ParityEven: options.c_cflag |= PARENB; // PARENB:产生奇偶位,执行奇偶校验 options.c_cflag &= ~PARODD; // PARODD:若设置则为奇校验,否则为偶校验 options.c_cflag |= INPCK; // INPCK:使奇偶校验起作用 options.c_cflag |= ISTRIP; // ISTRIP:若设置则有效输入数字被剥离7个字节,否则保留全部8位 break; /*设为空格,即停止位为2位*/ case itas109::ParitySpace: options.c_cflag &= ~PARENB; // PARENB:产生奇偶位,执行奇偶校验 options.c_cflag &= ~CSTOPB; // CSTOPB:使用两位停止位 break; default: fprintf(stderr, "Unkown parity!\n"); return -1; } //设置数据位 switch (dataBits) { case itas109::DataBits5: options.c_cflag &= ~CSIZE; //屏蔽其它标志位 options.c_cflag |= CS5; break; case itas109::DataBits6: options.c_cflag &= ~CSIZE; //屏蔽其它标志位 options.c_cflag |= CS6; break; case itas109::DataBits7: options.c_cflag &= ~CSIZE; //屏蔽其它标志位 options.c_cflag |= CS7; break; case itas109::DataBits8: options.c_cflag &= ~CSIZE; //屏蔽其它标志位 options.c_cflag |= CS8; break; default: fprintf(stderr, "Unkown bits!\n"); return -1; } //停止位 switch (stopbits) { case itas109::StopOne: options.c_cflag &= ~CSTOPB; // CSTOPB:使用两位停止位 break; case itas109::StopOneAndHalf: fprintf(stderr, "POSIX does not support 1.5 stop bits!\n"); return -1; case itas109::StopTwo: options.c_cflag |= CSTOPB; // CSTOPB:使用两位停止位 break; default: fprintf(stderr, "Unkown stop!\n"); return -1; } //控制模式 options.c_cflag |= CLOCAL; //保证程序不占用串口 options.c_cflag |= CREAD; //保证程序可以从串口中读取数据 //流控制 switch (flowControl) { case itas109::FlowNone: ///< No flow control 无流控制 options.c_cflag &= ~CRTSCTS; break; case itas109::FlowHardware: ///< Hardware(RTS / CTS) flow control 硬件流控制 options.c_cflag |= CRTSCTS; break; case itas109::FlowSoftware: ///< Software(XON / XOFF) flow control 软件流控制 options.c_cflag |= IXON | IXOFF | IXANY; break; default: fprintf(stderr, "Unkown c_flow!\n"); return -1; } //设置输出模式为原始输出 options.c_oflag &= ~OPOST; // OPOST:若设置则按定义的输出处理,否则所有c_oflag失效 //设置本地模式为原始模式 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); /* *ICANON:允许规范模式进行输入处理 *ECHO:允许输入字符的本地回显 *ECHOE:在接收EPASE时执行Backspace,Space,Backspace组合 *ISIG:允许信号 */ options.c_iflag &= ~(BRKINT | ICRNL | INPCK | ISTRIP | IXON); /* *BRKINT:如果设置了IGNBRK,BREAK键输入将被忽略 *ICRNL:将输入的回车转化成换行(如果IGNCR未设置的情况下)(0x0d => 0x0a) *INPCK:允许输入奇偶校验 *ISTRIP:去除字符的第8个比特 *IXON:允许输出时对XON/XOFF流进行控制 (0x11 0x13) */ //设置等待时间和最小接受字符 options.c_cc[VTIME] = 0; //可以在select中设置 options.c_cc[VMIN] = 1; //最少读取一个字符 //如果发生数据溢出,只接受数据,但是不进行读操作 tcflush(fd, TCIFLUSH); //激活配置 if (tcsetattr(fd, TCSANOW, &options) < 0) { perror("tcsetattr failed"); return -1; } return 0; } /** * @brief thread monitor 多线程监视器 * */ static void *commThreadMonitor(void *pParam){ // Cast the void pointer passed to the thread back to // a pointer of CSerialPortWinBase class CSerialPortUnixBase *p_base = (CSerialPortUnixBase *)pParam; if (p_base) { for (; p_base->isThreadRunning();) { int readbytes = 0; // read前获取可读的字节数,不区分阻塞和非阻塞 ioctl(p_base->fd, FIONREAD, &readbytes); if (readbytes >= p_base->getMinByteReadNotify()) //设定字符数,默认为2 { p_base->readReady._emit(); } else { usleep(1); // fix high cpu usage on unix } } } else { // point null } pthread_exit(NULL); } /** * @brief start thread monitor 启动多线程监视器 * * @return * @retval true start success 启动成功 * @retval false start failed 启动失败 */ bool startThreadMonitor(){ bool bRet = true; // start read thread int ret = pthread_create(&m_monitorThread, NULL, commThreadMonitor, (void *)this); if (ret < 0) { bRet = false; printf("Create read thread error."); } return bRet; } /** * @brief stop thread monitor 停止多线程监视器 * * @return * @retval true stop success 停止成功 * @retval false stop failed 停止失败 */ bool stopThreadMonitor(){ m_isThreadRunning = false; pthread_join(m_monitorThread, NULL); return true; } public: sigslot::signal0<> readReady; ///< sigslot for read 读数据信号 private: std::string m_portName; int m_baudRate; itas109::Parity m_parity; itas109::DataBits m_dataBits; itas109::StopBits m_stopbits; itas109::FlowControl m_flowControl; int64_t m_readBufferSize; int fd; /* File descriptor for the port */ private: pthread_t m_monitorThread; /**< read thread */ bool m_isThreadRunning; pthread_mutex_t m_communicationMutex; ///< mutex }; #endif //__CSERIALPORTUNIXBASE_H__