38 #include <sys/select.h> 39 #include <IOKit/serial/ioss.h> 41 namespace rp{
namespace arch{
namespace net{
44 :
rp::hal::serial_rxtx()
52 raw_serial::~raw_serial()
58 bool raw_serial::open()
60 return open(_portName, _baudrate, _flags);
63 bool raw_serial::bind(
const char * portname, uint32_t baudrate, uint32_t flags)
65 strncpy(_portName, portname,
sizeof(_portName));
71 bool raw_serial::open(
const char * portname, uint32_t baudrate, uint32_t flags)
75 serial_fd =
::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
77 if (serial_fd == -1)
return false;
79 struct termios options, oldopt;
80 tcgetattr(serial_fd, &oldopt);
81 bzero(&options,
sizeof(
struct termios));
83 cfsetspeed(&options, B19200);
86 options.c_cflag |= (CLOCAL | CREAD);
89 options.c_cflag &= ~PARENB;
90 options.c_cflag &= ~CSTOPB;
92 options.c_cflag &= ~CSIZE;
93 options.c_cflag |= CS8;
96 options.c_cflag &= ~CNEW_RTSCTS;
99 options.c_iflag &= ~(IXON | IXOFF | IXANY);
102 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
104 options.c_oflag &= ~OPOST;
106 tcflush(serial_fd,TCIFLUSH);
108 if (tcsetattr(serial_fd, TCSANOW, &options))
114 printf(
"Setting serial port baudrate...\n");
116 speed_t speed = (speed_t)baudrate;
117 if (ioctl(serial_fd, IOSSIOSPEED, &speed)== -1) {
118 printf(
"Error calling ioctl(..., IOSSIOSPEED, ...) %s - %s(%d).\n",
119 portname, strerror(errno), errno);
132 void raw_serial::close()
146 if (data == NULL || size ==0)
return 0;
151 int ans = ::write(serial_fd, data + tx_len, size-tx_len);
153 if (ans == -1)
return tx_len;
156 required_tx_cnt = tx_len;
157 }
while (tx_len<size);
169 int ans = ::read(serial_fd, data, size);
171 if (ans == -1) ans=0;
172 required_rx_cnt = ans;
177 void raw_serial::flush(
_u32 flags)
179 tcflush(serial_fd,TCIFLUSH);
184 if (returned_size) *returned_size = required_tx_cnt;
192 if (returned_size) *returned_size = required_rx_cnt;
199 if (returned_size==NULL) returned_size=(
_word_size_t *)&length;
204 struct timeval timeout_val;
208 FD_SET(serial_fd, &input_set);
209 max_fd = serial_fd + 1;
212 timeout_val.tv_sec = timeout / 1000;
213 timeout_val.tv_usec = (timeout % 1000) * 1000;
217 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1)
return ANS_DEV_ERR;
218 if (*returned_size >= data_count)
227 int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
242 assert (FD_ISSET(serial_fd, &input_set));
245 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1)
return ANS_DEV_ERR;
246 if (*returned_size >= data_count)
252 int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
253 int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
254 if (remain_timeout > expect_remain_time)
255 usleep(expect_remain_time);
263 size_t raw_serial::rxqueue_count()
268 if (::ioctl(serial_fd, FIONREAD, &remaining) == -1)
return 0;
272 void raw_serial::setDTR()
276 uint32_t dtr_bit = TIOCM_DTR;
277 ioctl(serial_fd, TIOCMBIS, &dtr_bit);
280 void raw_serial::clearDTR()
284 uint32_t dtr_bit = TIOCM_DTR;
285 ioctl(serial_fd, TIOCMBIC, &dtr_bit);
288 void raw_serial::_init()
292 required_tx_cnt = required_rx_cnt = 0;
297 _u32 raw_serial::getTermBaudBitmap(
_u32 baud)
299 #define BAUD_CONV(_baud_) case _baud_: return _baud_ 333 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_)