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