00001
00002
00003
00004
00005
00006
00007
00008
00009 #include <stdio.h>
00010 #include <stdlib.h>
00011 #include <unistd.h>
00012 #include <string.h>
00013 #include <sys/types.h>
00014 #include <sys/socket.h>
00015 #include <netinet/in.h>
00016 #include <netdb.h>
00017 #include <poll.h>
00018
00019 #ifdef __APPLE__
00020 #include <architecture/byte_order.h>
00021 #else
00022 #include <endian.h>
00023 #endif
00024
00025 #include "shared_serial/LxSerial.h"
00026
00027
00028
00029 LxSerial::LxSerial()
00030 {
00031 hPort = INVALID_DEVICE_HANDLE;
00032
00033 b_clear_echo = false;
00034 b_hw_flow_control = false;
00035 b_socket = false;
00036 }
00037
00038
00039 std::string& LxSerial::get_port_name()
00040 {
00041 return s_port_name;
00042 }
00043
00044 void LxSerial::set_port_type(LxSerial::PortType port_type)
00045 {
00046 switch (port_type)
00047 {
00048 case RS232:
00049 b_rts = false;
00050 break;
00051
00052 case RS485_FTDI:
00053 b_rts = false;
00054 break;
00055
00056 case RS485_EXAR:
00057 b_rts = true;
00058 b_clear_echo = true;
00059 break;
00060
00061 case RS485_SMSC:
00062 b_rts = false;
00063 b_clear_echo = true;
00064 break;
00065
00066 case TCP:
00067 b_socket = true;
00068 b_rts = false;
00069 b_clear_echo = false;
00070 break;
00071
00072 default:
00073 perror("LxSerial: no port type specified");
00074 break;
00075 }
00076 }
00077
00078
00079 bool LxSerial::port_open(const std::string& portname, LxSerial::PortType port_type)
00080 {
00081
00082 set_port_type(port_type);
00083
00084 if (b_socket)
00085 {
00086 int optval = 1;
00087
00088 struct sockaddr_in addr;
00089 struct hostent *server;
00090
00091 hPort = socket(AF_INET, SOCK_STREAM, 0);
00092 setsockopt(hPort, SOL_SOCKET, SO_REUSEADDR, &optval, sizeof optval);
00093
00094 bzero((char *) &addr, sizeof(addr));
00095 addr.sin_family = AF_INET;
00096
00097 std::string host_name = portname.substr(0, portname.find(':'));
00098 std::string port_number = portname.substr(portname.find(':')+1);
00099
00100 server = gethostbyname(host_name.c_str());
00101 if (!server)
00102 {
00103 perror("unknown remote serial host name");
00104 return false;
00105 }
00106
00107 bcopy((char *)server->h_addr, (char *)&addr.sin_addr.s_addr, server->h_length);
00108 addr.sin_port = htons(atoi(port_number.c_str()));
00109
00110 if (connect(hPort,(struct sockaddr *) &addr,sizeof(addr)) < 0)
00111 {
00112 perror("error connecting to remote serial host");
00113 return false;
00114 }
00115 }
00116 else
00117 {
00118
00119 hPort = open(portname.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129 if (hPort < 0) {
00130 perror(" Could not open serial port, aborting");
00131 return false;
00132 }
00133
00134
00135 tcgetattr(hPort, &options);
00136 tcgetattr(hPort, &old_options);
00137
00138 cfsetispeed(&options, B115200);
00139 cfsetospeed(&options, B115200);
00140
00141
00142
00143
00144 options.c_cflag |= (CLOCAL|CREAD|CS8);
00145
00146
00147 options.c_cflag &= ~(CRTSCTS|PARENB|CSTOPB);
00148
00149
00150 if (b_hw_flow_control){
00151 options.c_cflag |= (CRTSCTS);
00152 }
00153
00154
00155 options.c_lflag &= ~(ECHO|ECHONL|ECHOE|ICANON|ISIG|IEXTEN);
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166 options.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL|IXON|IXOFF);
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180 options.c_oflag &= ~(OPOST);
00181
00182
00183
00184
00185
00186
00187
00188 options.c_cc[VMIN] = 0;
00189 options.c_cc[VTIME] = WAIT_FOR_DATA_DSEC;
00190
00191
00192
00193 if (b_rts){
00194 int msc = TIOCM_RTS;
00195 ioctl(hPort, TIOCMBIC, &msc);
00196 usleep(100);
00197 }
00198
00199
00200
00201 if (tcsetattr(hPort,TCSANOW, &options)!=0){
00202 perror("Error: Could not set serial port settings");
00203 return false;
00204 }
00205
00206 usleep(100);
00207 tcflush(hPort, TCIOFLUSH);
00208 }
00209
00210
00211 s_port_name = portname;
00212
00213 return true;
00214 }
00215
00216 bool LxSerial::is_port_open()
00217 {
00218 return hPort >= 0;
00219 }
00220
00221
00222 bool LxSerial::set_speed( LxSerial::PortSpeed baudrate )
00223 {
00224 if (b_socket)
00225 return false;
00226
00227 #ifdef __APPLE__
00228 int speed = baudrate;
00229 if ( ioctl( hPort, IOSSIOSPEED, &speed ) == -1 )
00230 {
00231 perror("Error: Could not set serial port baudrate");
00232 return false;
00233 }
00234 #else
00235 cfsetispeed(&options, baudrate);
00236 cfsetospeed(&options, baudrate);
00237
00238 if (tcsetattr(hPort,TCSANOW, &options)!=0){
00239 perror("Error: Could not set serial port baudrate");
00240 return false;
00241 }
00242 usleep(100);
00243 tcflush(hPort, TCIOFLUSH);
00244 #endif
00245 return true;
00246 }
00247
00248 bool LxSerial::set_speed_int(const int baudrate)
00249 {
00250 LxSerial::PortSpeed baud;
00251
00252 switch (baudrate)
00253 {
00254 case 4000000: baud = S4000000; break;
00255 case 3500000: baud = S3500000; break;
00256 case 3000000: baud = S3000000; break;
00257 case 2500000: baud = S2500000; break;
00258 case 2000000: baud = S2000000; break;
00259 case 1500000: baud = S1500000; break;
00260 case 1152000: baud = S1152000; break;
00261 case 1000000: baud = S1000000; break;
00262 case 921600: baud = S921600; break;
00263 case 576000: baud = S576000; break;
00264 case 500000: baud = S500000; break;
00265 case 460800: baud = S460800; break;
00266 case 230400: baud = S230400; break;
00267 case 115200: baud = S115200; break;
00268 case 57600: baud = S57600; break;
00269 case 38400: baud = S38400; break;
00270 case 19200: baud = S19200; break;
00271 case 9600: baud = S9600; break;
00272 case 4800: baud = S4800; break;
00273 case 2400: baud = S2400; break;
00274 case 1800: baud = S1800; break;
00275 case 1200: baud = S1200; break;
00276 case 600: baud = S600; break;
00277 case 300: baud = S300; break;
00278 case 200: baud = S200; break;
00279 case 150: baud = S150; break;
00280 case 134: baud = S134; break;
00281 case 110: baud = S110; break;
00282 case 75: baud = S75; break;
00283 case 50: baud = S50; break;
00284 default:
00285 printf("This is not a legal portspeed!\n");
00286 return false;
00287 }
00288
00289 set_speed(baud);
00290 return true;
00291 }
00292
00293
00294 void LxSerial::set_clear_echo(bool clear)
00295 {
00296 b_clear_echo = clear;
00297 }
00298
00299
00300 bool LxSerial::port_close()
00301 {
00302 if (hPort==INVALID_DEVICE_HANDLE)
00303 return true;
00304
00305 if (!b_socket)
00306 {
00307 if (tcsetattr(hPort,TCSANOW, &old_options)!=0) {
00308 perror("Warning: Could not restore serial port settings.");
00309 }
00310 }
00311
00312 if(close(hPort) == -1) {
00313 perror("Error: Could not close serial port.");
00314 return false;
00315 }
00316 hPort = INVALID_DEVICE_HANDLE;
00317 return true;
00318 }
00319
00320 int LxSerial::port_read(unsigned char* buffer, int numBytes) const
00321 {
00322 int nBytesRead = read(hPort, buffer, numBytes);
00323
00324 #ifdef __DBG__
00325 printf("read ");
00326 for (int i=0;i<nBytesRead;i++)
00327 { printf("%02X ",buffer[i]); }
00328 printf("(%d)\n",nBytesRead);
00329 #endif
00330
00331 return nBytesRead;
00332 }
00333
00334 int LxSerial::port_read(unsigned char* buffer, int numBytes, int seconds, int microseconds)
00335 {
00336
00337 int s = seconds;
00338 int us = microseconds;
00339 int nBytesRead = 0;
00340 while (nBytesRead < numBytes)
00341 {
00342 if( wait_for_input( &s, &us) )
00343 {
00344 int partialRead = read(hPort, buffer + nBytesRead, numBytes - nBytesRead);
00345 nBytesRead += partialRead;
00346 }
00347 else if (nBytesRead < 0)
00348 {
00349 #ifdef __DBG__
00350 printf("Read Timeout... \n");
00351 #endif
00352 return READ_ERROR;
00353 }
00354 else
00355 break;
00356 }
00357
00358 #ifdef __DBG__
00359 printf("read ");
00360 for (int i=0;i<nBytesRead;i++)
00361 { printf("%02X ",buffer[i]); }
00362 printf("(%d)\n",nBytesRead);
00363 #endif
00364
00365 return nBytesRead;
00366 }
00367
00368 bool LxSerial::wait_for_input(int *seconds, int *microseconds)
00369 {
00370 fd_set readset;
00371 timeval timeout;
00372 timeout.tv_sec = *seconds;
00373 timeout.tv_usec = *microseconds;
00374 FD_ZERO(&readset);
00375 FD_SET(hPort, &readset);
00376 int res = select(hPort+1, &readset, NULL, NULL, &timeout);
00377 *seconds = timeout.tv_sec;
00378 *microseconds = timeout.tv_usec;
00379 return res == 1;
00380 }
00381
00382 int LxSerial::port_write(unsigned char* buffer, int numBytes)
00383 {
00384 int msc = TIOCM_RTS;
00385 if (b_rts){
00386 ioctl(hPort, TIOCMBIS, &msc);
00387 usleep(1000);
00388 }
00389
00390 int numBytesWritten = write(hPort, buffer, numBytes);
00391
00392 if (numBytes != numBytesWritten){
00393 perror("Error while writing to serial port");
00394 assert(numBytes == numBytesWritten);
00395 }
00396
00397 #ifdef __DBG__
00398 printf("write ");
00399 for (int i=0;i<numBytes;i++)
00400 { printf("%02X ",buffer[i]); }
00401 printf("(%d)",numBytesWritten);
00402 printf("\n");
00403 #endif
00404
00405 tcdrain(hPort);
00406
00407 if (b_rts){
00408 ioctl(hPort, TIOCMBIC, &msc);
00409 }
00410
00411 if (b_clear_echo)
00412 {
00413 unsigned char* echo_buffer = new unsigned char[numBytes];
00414 int nBytesRead = 0;
00415 int s = ECHO_WAIT_TIME_SEC;
00416 int us = ECHO_WAIT_TIME_USEC;
00417 while (nBytesRead < numBytesWritten)
00418 {
00419 if (wait_for_input(&s , &us))
00420 nBytesRead = read(hPort, echo_buffer + nBytesRead, numBytes - nBytesRead);
00421 else
00422 {
00423 #ifdef __DBG__
00424 printf("echo read back timeout\n");
00425 #endif
00426 delete[] echo_buffer;
00427 return ECHO_TIMEOUT_ERROR;
00428 }
00429 }
00430
00431
00432 #ifdef __DBG__
00433 printf("echo ");
00434 for (int i=0;i<nBytesRead;i++)
00435 { printf("%02X ",buffer[i]); }
00436 printf("(%d)\n",nBytesRead);
00437 #endif
00438
00439 if (nBytesRead!=numBytesWritten)
00440 {
00441 #ifdef __DBG__
00442 printf("Warning: nr. of characters echoed not correct\n");
00443 #endif
00444 delete[] echo_buffer;
00445 return READ_ERROR;
00446 }
00447
00448 if (memcmp(buffer,echo_buffer, numBytes)!=0)
00449 {
00450 #ifdef __DBG__
00451 printf("collition detect\n");
00452 #endif
00453 usleep(COLLISION_WAIT_TIME_USEC);
00454 tcflush(hPort, TCIFLUSH);
00455 delete[] echo_buffer;
00456 return COLLISION_DETECT_ERROR;
00457 }
00458 delete[] echo_buffer;
00459 }
00460
00461 return numBytesWritten;
00462 }
00463
00464 void LxSerial::flush_buffer()
00465 {
00466 tcflush(hPort, TCIOFLUSH);
00467 }
00468
00469 LxSerial::~LxSerial()
00470 {
00471 if (hPort != INVALID_DEVICE_HANDLE)
00472 port_close();
00473 }