Go to the documentation of this file.00001
00002 #include <stdio.h>
00003 #include <termios.h>
00004 #include <fcntl.h>
00005 #include <unistd.h>
00006 #include <sys/time.h>
00007 #include <sys/select.h>
00008
00009 #include <string>
00010 #include <iostream>
00011
00013 #include <cob_3d_mapping_demonstrator/serial_device.h>
00014
00015 SerialDevice::SerialDevice()
00016 {
00017
00018 }
00019
00020 SerialDevice::~SerialDevice()
00021 {
00022
00023
00024
00025
00026
00027 }
00028
00029 int SerialDevice::openPort(std::string device, int baud, int Parity, int StopBits)
00030 {
00031 int BAUD, DATABITS, STOPBITS, PARITYON, PARITY;
00032 struct termios config;
00033
00034
00035 switch(baud)
00036 {
00037 case 57600:
00038 BAUD = B57600;
00039 break;
00040 case 38400:
00041 BAUD = B38400;
00042 break;
00043 case 19200:
00044 BAUD = B19200;
00045 break;
00046 case 9600:
00047 default:
00048 BAUD = B9600;
00049 break;
00050 }
00051 switch (Parity)
00052 {
00053 case 0:
00054 default:
00055 PARITYON = 0;
00056 PARITY = 0;
00057 break;
00058 case 1:
00059 PARITYON = PARENB;
00060 PARITY = PARODD;
00061 break;
00062 case 2:
00063 PARITYON = PARENB;
00064 PARITY = 0;
00065 break;
00066 }
00067 device = device.insert(0,"/dev/");
00068
00070 fd_ = open(device.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
00071
00073 if (fd_ == -1 ) {
00074 return -1;
00075 }
00076
00078
00079
00080
00081 fcntl(fd_, F_SETFL, 0);
00082
00083 tcgetattr(fd_, &config);
00084
00086 cfsetispeed(&config, BAUD);
00087 cfsetospeed(&config, BAUD);
00088
00090 STOPBITS = StopBits;
00091
00093 DATABITS = CS8;
00094
00096
00097
00098
00099 config.c_cflag &= ~CRTSCTS;
00100 config.c_cflag = BAUD | DATABITS | STOPBITS | PARITYON | PARITY | CLOCAL | CREAD;
00101 config.c_iflag |= INPCK | ISTRIP ;
00102 config.c_iflag &= ~(IXON | IXOFF | IXANY );
00103 config.c_oflag = 0;
00104 config.c_lflag |= ICANON | ISIG ;
00105
00106
00108
00109 if(tcsetattr(fd_, TCSANOW, &config) < 0)
00110 {
00111 return -1;
00112 }
00113
00115 FlushInBuffer();
00116 FlushOutBuffer();
00117 PutString("E\n");
00118 return 0;
00119 }
00120
00121 void SerialDevice::closePort()
00122 {
00123 close(fd_);
00124 }
00125
00126 bool SerialDevice::checkIfStillThere()
00127 {
00128 return isatty(fd_);
00129 }
00130
00131 int SerialDevice::PutString(std::string str)
00132 {
00133 int res;
00134
00136 res = write(fd_, str.c_str(), str.size());
00137
00138 return res;
00139 }
00140
00141 void SerialDevice::GetString( std::string& rxstr )
00142 {
00143 char buf[255];
00144 size_t nbytes;
00145
00146 nbytes = read(fd_, buf, 255);
00147
00148 for(unsigned int i=0; i<nbytes; i++)
00149 {
00150 if(buf[i] == '\n')
00151 break;
00152 rxstr.push_back(buf[i]);
00153 }
00154 }
00155
00156 void SerialDevice::GetStringWithEndline( std::string& rxstr )
00157 {
00158 char buf[255];
00159 size_t nbytes;
00160
00161 nbytes = read(fd_, buf, 255);
00162
00163 for(unsigned int i=0; i<nbytes; i++)
00164 {
00165
00166
00167 rxstr.push_back(buf[i]);
00168 }
00169 }
00170
00171 bool SerialDevice::FlushInBuffer()
00172 {
00173 if( tcflush(fd_, TCIFLUSH) == -1 )
00174 return 0;
00175 else
00176 return 1;
00177 }
00178
00179
00180 bool SerialDevice::FlushOutBuffer()
00181 {
00182 if( tcflush(fd_, TCOFLUSH) == -1 )
00183 return 0;
00184 else
00185 return 1;
00186 }
00187
00188 unsigned char SerialDevice::GetChar()
00189 {
00190 unsigned char c;
00191 size_t n_bytes;
00192 n_bytes = read(fd_, &c, 1);
00193
00194 return c;
00195 }