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