38 #include <sys/select.h> 40 namespace rp{
namespace arch{
namespace net{
43 :
rp::hal::serial_rxtx()
51 raw_serial::~raw_serial()
57 bool raw_serial::open()
59 return open(_portName, _baudrate, _flags);
62 bool raw_serial::bind(
const char * portname, uint32_t baudrate, uint32_t flags)
64 strncpy(_portName, portname,
sizeof(_portName));
70 bool raw_serial::open(
const char * portname, uint32_t baudrate, uint32_t flags)
74 serial_fd =
::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
76 if (serial_fd == -1)
return false;
78 struct termios options, oldopt;
79 tcgetattr(serial_fd, &oldopt);
80 bzero(&options,
sizeof(
struct termios));
82 _u32 termbaud = getTermBaudBitmap(baudrate);
84 if (termbaud == (
_u32)-1) {
85 fprintf(stderr,
"Baudrate %d is not supported on macOS\r\n", baudrate);
89 cfsetispeed(&options, termbaud);
90 cfsetospeed(&options, termbaud);
93 options.c_cflag |= (CLOCAL | CREAD);
96 options.c_cflag &= ~PARENB;
97 options.c_cflag &= ~CSTOPB;
99 options.c_cflag &= ~CSIZE;
100 options.c_cflag |= CS8;
103 options.c_cflag &= ~CNEW_RTSCTS;
106 options.c_iflag &= ~(IXON | IXOFF | IXANY);
109 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
111 options.c_oflag &= ~OPOST;
113 tcflush(serial_fd,TCIFLUSH);
121 if (tcsetattr(serial_fd, TCSANOW, &options))
135 void raw_serial::close()
149 if (data == NULL || size ==0)
return 0;
154 int ans = ::write(serial_fd, data + tx_len, size-tx_len);
156 if (ans == -1)
return tx_len;
159 required_tx_cnt = tx_len;
160 }
while (tx_len<size);
172 int ans = ::read(serial_fd, data, size);
174 if (ans == -1) ans=0;
175 required_rx_cnt = ans;
180 void raw_serial::flush(
_u32 flags)
182 tcflush(serial_fd,TCIFLUSH);
187 if (returned_size) *returned_size = required_tx_cnt;
195 if (returned_size) *returned_size = required_rx_cnt;
202 if (returned_size==NULL) returned_size=(
_word_size_t *)&length;
207 struct timeval timeout_val;
211 FD_SET(serial_fd, &input_set);
212 max_fd = serial_fd + 1;
215 timeout_val.tv_sec = timeout / 1000;
216 timeout_val.tv_usec = (timeout % 1000) * 1000;
220 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1)
return ANS_DEV_ERR;
221 if (*returned_size >= data_count)
230 int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
245 assert (FD_ISSET(serial_fd, &input_set));
248 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1)
return ANS_DEV_ERR;
249 if (*returned_size >= data_count)
255 int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
256 int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
257 if (remain_timeout > expect_remain_time)
258 usleep(expect_remain_time);
266 size_t raw_serial::rxqueue_count()
271 if (::ioctl(serial_fd, FIONREAD, &remaining) == -1)
return 0;
275 void raw_serial::setDTR()
279 uint32_t dtr_bit = TIOCM_DTR;
280 ioctl(serial_fd, TIOCMBIS, &dtr_bit);
283 void raw_serial::clearDTR()
287 uint32_t dtr_bit = TIOCM_DTR;
288 ioctl(serial_fd, TIOCMBIC, &dtr_bit);
291 void raw_serial::_init()
295 required_tx_cnt = required_rx_cnt = 0;
300 _u32 raw_serial::getTermBaudBitmap(
_u32 baud)
302 #define BAUD_CONV(_baud_) case _baud_: return _baud_ 336 namespace rp{
namespace hal{
static serial_rxtx * CreateRxTx()
static void ReleaseRxTx(serial_rxtx *)
volatile bool _is_serial_opened
virtual void clearDTR()=0
typedef _word_size_t(THREAD_PROC *thread_proc_t)(void *)
#define BAUD_CONV(_baud_)