49 #include <sys/select.h>    55 #include <asm/ioctls.h>    56 #include <asm/termbits.h>    57 #include <sys/ioctl.h>    58 extern "C" int tcflush(
int fildes, 
int queue_selector);
    62 #include <sys/ioctl.h>    67 namespace rp{ 
namespace arch{ 
namespace net{
    70     : 
rp::hal::serial_rxtx()
   107 #if !defined(__GNUC__)   109     struct termios options, oldopt;
   111     bzero(&options,
sizeof(
struct termios));
   114     options.c_cflag |= (CLOCAL | CREAD);
   118     if (termbaud == (
_u32)-1) {
   122     cfsetispeed(&options, termbaud);
   123     cfsetospeed(&options, termbaud);
   125     options.c_cflag &= ~PARENB; 
   126     options.c_cflag &= ~CSTOPB; 
   127     options.c_cflag &= ~CRTSCTS; 
   129     options.c_cflag &= ~CSIZE;
   130     options.c_cflag |= CS8; 
   133     options.c_cflag &= ~CNEW_RTSCTS; 
   136     options.c_iflag &= ~(IXON | IXOFF | IXANY); 
   139     options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
   141     options.c_oflag &= ~OPOST;
   145     if (tcsetattr(
serial_fd, TCSANOW, &options))
   157     bzero(&tio, 
sizeof(
struct termios2));
   159     tio.c_cflag = BOTHER;
   160     tio.c_cflag |= (CLOCAL | CREAD | CS8); 
   162     tio.c_cflag &= ~CSTOPB;   
   163     tio.c_cflag &= ~CRTSCTS;  
   164     tio.c_cflag &= ~PARENB;   
   167     tio.c_cflag &= ~CNEW_RTSCTS; 
   170     tio.c_iflag &= ~(IXON | IXOFF | IXANY); 
   176     tio.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
   178     tio.c_oflag &= ~OPOST;
   180     tio.c_ispeed = baudrate;
   181     tio.c_ospeed = baudrate;
   207         int flags = fcntl(
_selfpipe[0], F_GETFL);
   212         if (fcntl(
_selfpipe[0], F_SETFL, flags) == -1)
   220         if (fcntl(
_selfpipe[1], F_SETFL, flags) == -1)
   251     if (data == NULL || size ==0) 
return 0;
   256         int ans = ::write(
serial_fd, data + tx_len, size-tx_len);
   258         if (ans == -1) 
return tx_len;
   262     }
while (tx_len<size);
   275     if (ans == -1) ans=0;
   303     if (returned_size==NULL) returned_size=(
size_t *)&length;
   308     struct timeval timeout_val;
   320     timeout_val.tv_sec = timeout / 1000;
   321     timeout_val.tv_usec = (timeout % 1000) * 1000;
   325         if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) 
return ANS_DEV_ERR;
   326         if (*returned_size >= data_count)
   335         int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
   351             if (FD_ISSET(
_selfpipe[0], &input_set)) {   
   355                     if (::read(
_selfpipe[0], &ch, 1) == -1) {
   367             assert (FD_ISSET(serial_fd, &input_set));
   370             if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) 
return ANS_DEV_ERR;
   371             if (*returned_size >= data_count)
   377                 int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
   378                 int expect_remain_time = (data_count - *returned_size)*1000000*8/
_baudrate;
   379                 if (remain_timeout > expect_remain_time)
   380                     usleep(expect_remain_time);
   394     if (::ioctl(
serial_fd, FIONREAD, &remaining) == -1) 
return 0;
   402     uint32_t dtr_bit = TIOCM_DTR;
   410     uint32_t dtr_bit = TIOCM_DTR;
   433 #define BAUD_CONV( _baud_) case _baud_:  return B##_baud_    464 namespace rp{ 
namespace hal{
 
virtual void flush(_u32 flags)
virtual int waitfordata(size_t data_count, _u32 timeout=-1, size_t *returned_size=NULL)
virtual int waitforsent(_u32 timeout=-1, size_t *returned_size=NULL)
#define BAUD_CONV(_baud_)
virtual size_t rxqueue_count()
volatile bool _is_serial_opened
virtual bool bind(const char *portname, uint32_t baudrate, uint32_t flags=0)
virtual int senddata(const unsigned char *data, size_t size)
virtual int recvdata(unsigned char *data, size_t size)
_u32 getTermBaudBitmap(_u32 baud)
virtual int waitforrecv(_u32 timeout=-1, size_t *returned_size=NULL)
virtual void cancelOperation()