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/linux/arch_linux.h"
00036 #include <stdio.h>
00037 #include <stdlib.h>
00038 #include <string.h>
00039 #include <unistd.h>
00040 #include <assert.h>
00041
00042
00043 #include <errno.h>
00044 #include <fcntl.h>
00045
00046 #include <time.h>
00047 #include "hal/types.h"
00048 #include "arch/linux/net_serial.h"
00049 #include <sys/select.h>
00050
00051 #include <algorithm>
00052
00053 #if defined(__GNUC__)
00054
00055 #include <asm/ioctls.h>
00056 #include <asm/termbits.h>
00057 #include <sys/ioctl.h>
00058 extern "C" int tcflush(int fildes, int queue_selector);
00059 #else
00060
00061 #include <termios.h>
00062 #include <sys/ioctl.h>
00063
00064 #endif
00065
00066
00067 namespace rp{ namespace arch{ namespace net{
00068
00069 raw_serial::raw_serial()
00070 : rp::hal::serial_rxtx()
00071 , _baudrate(0)
00072 , _flags(0)
00073 , serial_fd(-1)
00074 {
00075 _init();
00076 }
00077
00078 raw_serial::~raw_serial()
00079 {
00080 close();
00081
00082 }
00083
00084 bool raw_serial::open()
00085 {
00086 return open(_portName, _baudrate, _flags);
00087 }
00088
00089 bool raw_serial::bind(const char * portname, uint32_t baudrate, uint32_t flags)
00090 {
00091 strncpy(_portName, portname, sizeof(_portName));
00092 _baudrate = baudrate;
00093 _flags = flags;
00094 return true;
00095 }
00096
00097 bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
00098 {
00099 if (isOpened()) close();
00100
00101 serial_fd = ::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
00102
00103 if (serial_fd == -1) return false;
00104
00105
00106
00107 #if !defined(__GNUC__)
00108
00109 struct termios options, oldopt;
00110 tcgetattr(serial_fd, &oldopt);
00111 bzero(&options,sizeof(struct termios));
00112
00113
00114 options.c_cflag |= (CLOCAL | CREAD);
00115
00116 _u32 termbaud = getTermBaudBitmap(baudrate);
00117
00118 if (termbaud == (_u32)-1) {
00119 close();
00120 return false;
00121 }
00122 cfsetispeed(&options, termbaud);
00123 cfsetospeed(&options, termbaud);
00124
00125 options.c_cflag &= ~PARENB;
00126 options.c_cflag &= ~CSTOPB;
00127 options.c_cflag &= ~CRTSCTS;
00128
00129 options.c_cflag &= ~CSIZE;
00130 options.c_cflag |= CS8;
00131
00132 #ifdef CNEW_RTSCTS
00133 options.c_cflag &= ~CNEW_RTSCTS;
00134 #endif
00135
00136 options.c_iflag &= ~(IXON | IXOFF | IXANY);
00137
00138
00139 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
00140
00141 options.c_oflag &= ~OPOST;
00142
00143
00144
00145 if (tcsetattr(serial_fd, TCSANOW, &options))
00146 {
00147 close();
00148 return false;
00149 }
00150
00151 #else
00152
00153
00154 struct termios2 tio;
00155
00156 ioctl(serial_fd, TCGETS2, &tio);
00157 bzero(&tio, sizeof(struct termios2));
00158
00159 tio.c_cflag = BOTHER;
00160 tio.c_cflag |= (CLOCAL | CREAD | CS8);
00161
00162 tio.c_cflag &= ~CSTOPB;
00163 tio.c_cflag &= ~CRTSCTS;
00164 tio.c_cflag &= ~PARENB;
00165
00166 #ifdef CNEW_RTSCTS
00167 tio.c_cflag &= ~CNEW_RTSCTS;
00168 #endif
00169
00170 tio.c_iflag &= ~(IXON | IXOFF | IXANY);
00171
00172
00173 tio.c_cc[VMIN] = 0;
00174 tio.c_cc[VTIME] = 0;
00175
00176 tio.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
00177
00178 tio.c_oflag &= ~OPOST;
00179
00180 tio.c_ispeed = baudrate;
00181 tio.c_ospeed = baudrate;
00182
00183
00184 ioctl(serial_fd, TCSETS2, &tio);
00185
00186 #endif
00187
00188
00189 tcflush(serial_fd, TCIFLUSH);
00190
00191 if (fcntl(serial_fd, F_SETFL, FNDELAY))
00192 {
00193 close();
00194 return false;
00195 }
00196
00197
00198 _is_serial_opened = true;
00199 _operation_aborted = false;
00200
00201
00202 clearDTR();
00203 do {
00204
00205 if (pipe(_selfpipe) == -1) break;
00206
00207 int flags = fcntl(_selfpipe[0], F_GETFL);
00208 if (flags == -1)
00209 break;
00210
00211 flags |= O_NONBLOCK;
00212 if (fcntl(_selfpipe[0], F_SETFL, flags) == -1)
00213 break;
00214
00215 flags = fcntl(_selfpipe[1], F_GETFL);
00216 if (flags == -1)
00217 break;
00218
00219 flags |= O_NONBLOCK;
00220 if (fcntl(_selfpipe[1], F_SETFL, flags) == -1)
00221 break;
00222
00223 } while (0);
00224
00225 return true;
00226 }
00227
00228 void raw_serial::close()
00229 {
00230 if (serial_fd != -1)
00231 ::close(serial_fd);
00232 serial_fd = -1;
00233
00234 if (_selfpipe[0] != -1)
00235 ::close(_selfpipe[0]);
00236
00237 if (_selfpipe[1] != -1)
00238 ::close(_selfpipe[1]);
00239
00240 _selfpipe[0] = _selfpipe[1] = -1;
00241
00242 _operation_aborted = false;
00243 _is_serial_opened = false;
00244 }
00245
00246 int raw_serial::senddata(const unsigned char * data, size_t size)
00247 {
00248
00249 if (!isOpened()) return 0;
00250
00251 if (data == NULL || size ==0) return 0;
00252
00253 size_t tx_len = 0;
00254 required_tx_cnt = 0;
00255 do {
00256 int ans = ::write(serial_fd, data + tx_len, size-tx_len);
00257
00258 if (ans == -1) return tx_len;
00259
00260 tx_len += ans;
00261 required_tx_cnt = tx_len;
00262 }while (tx_len<size);
00263
00264
00265 return tx_len;
00266 }
00267
00268
00269 int raw_serial::recvdata(unsigned char * data, size_t size)
00270 {
00271 if (!isOpened()) return 0;
00272
00273 int ans = ::read(serial_fd, data, size);
00274
00275 if (ans == -1) ans=0;
00276 required_rx_cnt = ans;
00277 return ans;
00278 }
00279
00280
00281 void raw_serial::flush( _u32 flags)
00282 {
00283 tcflush(serial_fd,TCIFLUSH);
00284 }
00285
00286 int raw_serial::waitforsent(_u32 timeout, size_t * returned_size)
00287 {
00288 if (returned_size) *returned_size = required_tx_cnt;
00289 return 0;
00290 }
00291
00292 int raw_serial::waitforrecv(_u32 timeout, size_t * returned_size)
00293 {
00294 if (!isOpened() ) return -1;
00295
00296 if (returned_size) *returned_size = required_rx_cnt;
00297 return 0;
00298 }
00299
00300 int raw_serial::waitfordata(size_t data_count, _u32 timeout, size_t * returned_size)
00301 {
00302 size_t length = 0;
00303 if (returned_size==NULL) returned_size=(size_t *)&length;
00304 *returned_size = 0;
00305
00306 int max_fd;
00307 fd_set input_set;
00308 struct timeval timeout_val;
00309
00310
00311 FD_ZERO(&input_set);
00312 FD_SET(serial_fd, &input_set);
00313
00314 if (_selfpipe[0] != -1)
00315 FD_SET(_selfpipe[0], &input_set);
00316
00317 max_fd = std::max<int>(serial_fd, _selfpipe[0]) + 1;
00318
00319
00320 timeout_val.tv_sec = timeout / 1000;
00321 timeout_val.tv_usec = (timeout % 1000) * 1000;
00322
00323 if ( isOpened() )
00324 {
00325 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
00326 if (*returned_size >= data_count)
00327 {
00328 return 0;
00329 }
00330 }
00331
00332 while ( isOpened() )
00333 {
00334
00335 int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
00336
00337 if (n < 0)
00338 {
00339
00340 *returned_size = 0;
00341 return ANS_DEV_ERR;
00342 }
00343 else if (n == 0)
00344 {
00345
00346 *returned_size =0;
00347 return ANS_TIMEOUT;
00348 }
00349 else
00350 {
00351 if (FD_ISSET(_selfpipe[0], &input_set)) {
00352
00353 int ch;
00354 for (;;) {
00355 if (::read(_selfpipe[0], &ch, 1) == -1) {
00356 break;
00357 }
00358
00359 }
00360
00361
00362 *returned_size = 0;
00363 return ANS_TIMEOUT;
00364 }
00365
00366
00367 assert (FD_ISSET(serial_fd, &input_set));
00368
00369
00370 if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
00371 if (*returned_size >= data_count)
00372 {
00373 return 0;
00374 }
00375 else
00376 {
00377 int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
00378 int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
00379 if (remain_timeout > expect_remain_time)
00380 usleep(expect_remain_time);
00381 }
00382 }
00383
00384 }
00385
00386 return ANS_DEV_ERR;
00387 }
00388
00389 size_t raw_serial::rxqueue_count()
00390 {
00391 if ( !isOpened() ) return 0;
00392 size_t remaining;
00393
00394 if (::ioctl(serial_fd, FIONREAD, &remaining) == -1) return 0;
00395 return remaining;
00396 }
00397
00398 void raw_serial::setDTR()
00399 {
00400 if ( !isOpened() ) return;
00401
00402 uint32_t dtr_bit = TIOCM_DTR;
00403 ioctl(serial_fd, TIOCMBIS, &dtr_bit);
00404 }
00405
00406 void raw_serial::clearDTR()
00407 {
00408 if ( !isOpened() ) return;
00409
00410 uint32_t dtr_bit = TIOCM_DTR;
00411 ioctl(serial_fd, TIOCMBIC, &dtr_bit);
00412 }
00413
00414 void raw_serial::_init()
00415 {
00416 serial_fd = -1;
00417 _portName[0] = 0;
00418 required_tx_cnt = required_rx_cnt = 0;
00419 _operation_aborted = false;
00420 _selfpipe[0] = _selfpipe[1] = -1;
00421 }
00422
00423 void raw_serial::cancelOperation()
00424 {
00425 _operation_aborted = true;
00426 if (_selfpipe[1] == -1) return;
00427
00428 ::write(_selfpipe[1], "x", 1);
00429 }
00430
00431 _u32 raw_serial::getTermBaudBitmap(_u32 baud)
00432 {
00433 #define BAUD_CONV( _baud_) case _baud_: return B##_baud_
00434 switch (baud) {
00435 BAUD_CONV(1200);
00436 BAUD_CONV(1800);
00437 BAUD_CONV(2400);
00438 BAUD_CONV(4800);
00439 BAUD_CONV(9600);
00440 BAUD_CONV(19200);
00441 BAUD_CONV(38400);
00442 BAUD_CONV(57600);
00443 BAUD_CONV(115200);
00444 BAUD_CONV(230400);
00445 BAUD_CONV(460800);
00446 BAUD_CONV(500000);
00447 BAUD_CONV(576000);
00448 BAUD_CONV(921600);
00449 BAUD_CONV(1000000);
00450 BAUD_CONV(1152000);
00451 BAUD_CONV(1500000);
00452 BAUD_CONV(2000000);
00453 BAUD_CONV(2500000);
00454 BAUD_CONV(3000000);
00455 BAUD_CONV(3500000);
00456 BAUD_CONV(4000000);
00457 }
00458 return -1;
00459 }
00460
00461 }}}
00462
00463
00464 namespace rp{ namespace hal{
00465
00466 serial_rxtx * serial_rxtx::CreateRxTx()
00467 {
00468 return new rp::arch::net::raw_serial();
00469 }
00470
00471 void serial_rxtx::ReleaseRxTx(serial_rxtx *rxtx)
00472 {
00473 delete rxtx;
00474 }
00475
00476 }}