00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "arch/macOS/arch_macOS.h"
00036 #include "arch/macOS/net_serial.h"
00037 #include <termios.h>
00038 #include <sys/select.h>
00039
00040 namespace rp{ namespace arch{ namespace net{
00041
00042 raw_serial::raw_serial()
00043 : rp::hal::serial_rxtx()
00044 , _baudrate(0)
00045 , _flags(0)
00046 , serial_fd(-1)
00047 {
00048 _init();
00049 }
00050
00051 raw_serial::~raw_serial()
00052 {
00053 close();
00054
00055 }
00056
00057 bool raw_serial::open()
00058 {
00059 return open(_portName, _baudrate, _flags);
00060 }
00061
00062 bool raw_serial::bind(const char * portname, uint32_t baudrate, uint32_t flags)
00063 {
00064 strncpy(_portName, portname, sizeof(_portName));
00065 _baudrate = baudrate;
00066 _flags = flags;
00067 return true;
00068 }
00069
00070 bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
00071 {
00072 if (isOpened()) close();
00073
00074 serial_fd = ::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
00075
00076 if (serial_fd == -1) return false;
00077
00078 struct termios options, oldopt;
00079 tcgetattr(serial_fd, &oldopt);
00080 bzero(&options,sizeof(struct termios));
00081
00082 _u32 termbaud = getTermBaudBitmap(baudrate);
00083
00084 if (termbaud == (_u32)-1) {
00085 fprintf(stderr, "Baudrate %d is not supported on macOS\r\n", baudrate);
00086 close();
00087 return false;
00088 }
00089 cfsetispeed(&options, termbaud);
00090 cfsetospeed(&options, termbaud);
00091
00092
00093 options.c_cflag |= (CLOCAL | CREAD);
00094
00095
00096 options.c_cflag &= ~PARENB;
00097 options.c_cflag &= ~CSTOPB;
00098
00099 options.c_cflag &= ~CSIZE;
00100 options.c_cflag |= CS8;
00101
00102 #ifdef CNEW_RTSCTS
00103 options.c_cflag &= ~CNEW_RTSCTS;
00104 #endif
00105
00106 options.c_iflag &= ~(IXON | IXOFF | IXANY);
00107
00108
00109 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
00110
00111 options.c_oflag &= ~OPOST;
00112
00113 tcflush(serial_fd,TCIFLUSH);
00114
00115
00116
00117
00118
00119
00120
00121 if (tcsetattr(serial_fd, TCSANOW, &options))
00122 {
00123 close();
00124 return false;
00125 }
00126
00127 _is_serial_opened = true;
00128
00129
00130 clearDTR();
00131
00132 return true;
00133 }
00134
00135 void raw_serial::close()
00136 {
00137 if (serial_fd != -1)
00138 ::close(serial_fd);
00139 serial_fd = -1;
00140
00141 _is_serial_opened = false;
00142 }
00143
00144 int raw_serial::senddata(const unsigned char * data, _word_size_t size)
00145 {
00146
00147 if (!isOpened()) return 0;
00148
00149 if (data == NULL || size ==0) return 0;
00150
00151 size_t tx_len = 0;
00152 required_tx_cnt = 0;
00153 do {
00154 int ans = ::write(serial_fd, data + tx_len, size-tx_len);
00155
00156 if (ans == -1) return tx_len;
00157
00158 tx_len += ans;
00159 required_tx_cnt = tx_len;
00160 }while (tx_len<size);
00161
00162
00163 return tx_len;
00164 }
00165
00166
00167
00168 int raw_serial::recvdata(unsigned char * data, _word_size_t size)
00169 {
00170 if (!isOpened()) return 0;
00171
00172 int ans = ::read(serial_fd, data, size);
00173
00174 if (ans == -1) ans=0;
00175 required_rx_cnt = ans;
00176 return ans;
00177 }
00178
00179
00180 void raw_serial::flush( _u32 flags)
00181 {
00182 tcflush(serial_fd,TCIFLUSH);
00183 }
00184
00185 int raw_serial::waitforsent(_u32 timeout, _word_size_t * returned_size)
00186 {
00187 if (returned_size) *returned_size = required_tx_cnt;
00188 return 0;
00189 }
00190
00191 int raw_serial::waitforrecv(_u32 timeout, _word_size_t * returned_size)
00192 {
00193 if (!isOpened() ) return -1;
00194
00195 if (returned_size) *returned_size = required_rx_cnt;
00196 return 0;
00197 }
00198
00199 int raw_serial::waitfordata(_word_size_t data_count, _u32 timeout, _word_size_t * returned_size)
00200 {
00201 _word_size_t length = 0;
00202 if (returned_size==NULL) returned_size=(_word_size_t *)&length;
00203 *returned_size = 0;
00204
00205 int max_fd;
00206 fd_set input_set;
00207 struct timeval timeout_val;
00208
00209
00210 FD_ZERO(&input_set);
00211 FD_SET(serial_fd, &input_set);
00212 max_fd = serial_fd + 1;
00213
00214
00215 timeout_val.tv_sec = timeout / 1000;
00216 timeout_val.tv_usec = (timeout % 1000) * 1000;
00217
00218 if ( isOpened() )
00219 {
00220 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
00221 if (*returned_size >= data_count)
00222 {
00223 return 0;
00224 }
00225 }
00226
00227 while ( isOpened() )
00228 {
00229
00230 int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
00231
00232 if (n < 0)
00233 {
00234
00235 return ANS_DEV_ERR;
00236 }
00237 else if (n == 0)
00238 {
00239
00240 return ANS_TIMEOUT;
00241 }
00242 else
00243 {
00244
00245 assert (FD_ISSET(serial_fd, &input_set));
00246
00247
00248 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
00249 if (*returned_size >= data_count)
00250 {
00251 return 0;
00252 }
00253 else
00254 {
00255 int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
00256 int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
00257 if (remain_timeout > expect_remain_time)
00258 usleep(expect_remain_time);
00259 }
00260 }
00261
00262 }
00263 return ANS_DEV_ERR;
00264 }
00265
00266 size_t raw_serial::rxqueue_count()
00267 {
00268 if ( !isOpened() ) return 0;
00269 size_t remaining;
00270
00271 if (::ioctl(serial_fd, FIONREAD, &remaining) == -1) return 0;
00272 return remaining;
00273 }
00274
00275 void raw_serial::setDTR()
00276 {
00277 if ( !isOpened() ) return;
00278
00279 uint32_t dtr_bit = TIOCM_DTR;
00280 ioctl(serial_fd, TIOCMBIS, &dtr_bit);
00281 }
00282
00283 void raw_serial::clearDTR()
00284 {
00285 if ( !isOpened() ) return;
00286
00287 uint32_t dtr_bit = TIOCM_DTR;
00288 ioctl(serial_fd, TIOCMBIC, &dtr_bit);
00289 }
00290
00291 void raw_serial::_init()
00292 {
00293 serial_fd = 0;
00294 _portName[0] = 0;
00295 required_tx_cnt = required_rx_cnt = 0;
00296 }
00297
00298
00299
00300 _u32 raw_serial::getTermBaudBitmap(_u32 baud)
00301 {
00302 #define BAUD_CONV(_baud_) case _baud_: return _baud_
00303 switch (baud)
00304 {
00305 BAUD_CONV(1200);
00306 BAUD_CONV(1800);
00307 BAUD_CONV(2400);
00308 BAUD_CONV(4800);
00309 BAUD_CONV(9600);
00310 BAUD_CONV(19200);
00311 BAUD_CONV(38400);
00312 BAUD_CONV(57600);
00313 BAUD_CONV(115200);
00314 BAUD_CONV(230400);
00315 BAUD_CONV(460800);
00316 BAUD_CONV(500000);
00317 BAUD_CONV(576000);
00318 BAUD_CONV(921600);
00319 BAUD_CONV(1000000);
00320 BAUD_CONV(1152000);
00321 BAUD_CONV(1500000);
00322 BAUD_CONV(2000000);
00323 BAUD_CONV(2500000);
00324 BAUD_CONV(3000000);
00325 BAUD_CONV(3500000);
00326 BAUD_CONV(4000000);
00327 }
00328 return -1;
00329 }
00330
00331 }}}
00332
00333
00334
00335
00336 namespace rp{ namespace hal{
00337
00338 serial_rxtx * serial_rxtx::CreateRxTx()
00339 {
00340 return new rp::arch::net::raw_serial();
00341 }
00342
00343 void serial_rxtx::ReleaseRxTx(serial_rxtx *rxtx)
00344 {
00345 delete rxtx;
00346 }
00347
00348 }}