43 #include <sys/select.h> 44 #include <sys/ioctl.h> 72 #define SDH_RS232_CYGWIN_DEBUG 1 78 #if SDH_RS232_CYGWIN_DEBUG 102 char* dup =
new char[strlen( s ) + 1];
103 return strcpy( dup, s );
107 cRS232::cRS232(
int _port,
unsigned long _baudrate,
double _timeout,
char const* _device_format_string ) :
111 device_format_string( _device_format_string ),
112 baudrate( _baudrate ),
126 DBG(
dbg <<
"Opening RS232 device '" << std::string(device) <<
"', baudrate: " <<
baudrate <<
"\n" );
128 fd = open( device, O_RDWR | O_NOCTTY | O_NDELAY );
155 io_set_new.c_cflag |= CLOCAL;
156 io_set_new.c_cflag |= HUPCL;
157 io_set_new.c_cflag |= CREAD;
158 io_set_new.c_cflag &= ~PARENB;
159 io_set_new.c_cflag &= ~CSTOPB;
160 io_set_new.c_cflag &= ~CSIZE;
161 io_set_new.c_cflag |= CS8;
162 io_set_new.c_cflag &= ~CRTSCTS;
163 io_set_new.c_cflag &= ~CBAUD;
168 io_set_new.c_oflag &= ~OPOST;
172 io_set_new.c_iflag &= ~INPCK;
173 io_set_new.c_iflag |= IGNPAR;
174 io_set_new.c_iflag &= ~ISTRIP;
176 io_set_new.c_iflag &= ~(IXON | IXOFF | IXANY);
177 io_set_new.c_iflag |= IGNBRK;
178 io_set_new.c_iflag &= ~BRKINT;
179 io_set_new.c_iflag &= ~INLCR;
180 io_set_new.c_iflag &= ~IGNCR;
181 io_set_new.c_iflag &= ~ICRNL;
182 io_set_new.c_iflag &= ~IUCLC;
183 io_set_new.c_iflag &= ~IMAXBEL;
188 io_set_new.c_lflag &= ~ICANON;
189 io_set_new.c_lflag &= ~ECHO;
190 io_set_new.c_lflag &= ~ECHOE;
191 io_set_new.c_lflag &= ~ISIG;
220 io_set_new.c_cc[VMIN] = 1;
221 io_set_new.c_cc[VTIME]= 0;
227 if (tcsetattr(
fd,TCSANOW,&io_set_new) < 0)
263 case 3000000:
return B3000000;
266 case 2500000:
return B2500000;
269 case 2000000:
return B2000000;
272 case 1500000:
return B1500000;
275 case 1152000:
return B1152000;
278 case 1000000:
return B1000000;
281 case 921600:
return B921600;
284 case 576000:
return B576000;
287 case 500000:
return B500000;
290 case 460800:
return B460800;
293 case 256000:
return B256000;
296 case 230400:
return B230400;
298 case 115200:
return B115200;
299 case 57600:
return B57600;
300 case 38400:
return B38400;
301 case 19200:
return B19200;
302 case 9600:
return B9600;
303 case 4800:
return B4800;
304 case 2400:
return B2400;
305 case 1800:
return B1800;
306 case 1200:
return B1200;
307 case 600:
return B600;
308 case 300:
return B300;
309 case 200:
return B200;
310 case 150:
return B150;
311 case 134:
return B134;
312 case 110:
return B110;
334 DBG(
dbg <<
"cRS232::write wrote " << len <<
"/" << written <<
" bytes (hex):" <<
cHexByteString( ptr, written ) <<
"\n" );
341 ssize_t
cRS232::Read(
void *data, ssize_t
size,
long timeout_us,
bool return_on_less_data )
350 char* buffer =(
char*) data;
351 long max_time_us = timeout_us;
352 if ( max_time_us <= 0 )
367 if ( max_time_us >= 0)
369 us_left = max_time_us - start_time.
Elapsed_us();
370 time_left.tv_sec = us_left / 1000000;
371 time_left.tv_usec = us_left % 1000000;
373 if (time_left.tv_sec <= 0 && time_left.tv_usec < 1 )
375 time_left.tv_sec = 0;
376 time_left.tv_usec = 1;
379 timeout_p = &time_left;
393 struct timeval timeout_maybe_overwritten = *timeout_p;
394 select_return = select(
fd+1, &fds,
NULL,
NULL, &timeout_maybe_overwritten );
397 if ( select_return < 0 )
404 else if (select_return > 0)
407 if (return_on_less_data)
410 bytes_read_inc = read(
fd, buffer + bytes_read, size - bytes_read );
413 if (bytes_read_inc < 0)
420 DBG(
dbg <<
"cRS232::Read: Read " << bytes_read_inc <<
"/" << (size-bytes_read) <<
" bytes (hex): " <<
cHexByteString( buffer+bytes_read, bytes_read_inc ) <<
"\n" );
422 if (bytes_read_inc>0)
424 bytes_read+=bytes_read_inc;
425 if (bytes_read==size)
445 int irc = ioctl(
fd, TIOCINQ, &bytes_read_inc );
458 if (bytes_read_inc>=size)
460 if ((bytes_read = read(
fd, data, size )) < 0)
469 DBG(
dbg <<
"cRS232::Read: Read " << bytes_read <<
"/" << size <<
" bytes (hex): " <<
cHexByteString( (
char const*) data, bytes_read ) <<
"\n" );
481 if (return_on_less_data)
488 while ( timeout_us < 0 || start_time.
Elapsed_us() < (long) max_time_us );
ssize_t Read(void *data, ssize_t size, long timeout_us, bool return_on_less_data)
USING_NAMESPACE_SDH char * StrDupNew(char *const s)
helper function, duplicate string s into a char array allocated with new[]
Interface of auxilliary utility functions for SDHLibrary-CPP.
std::string device_format_string
the sprintf format string to generate the device name from the port, see Constructor ...
dummy class for (debug) stream output of bytes as list of hex values
void Close(void)
Close the previously opened rs232 port.
Low-level communication class to access a serial port.
virtual void SetTimeout(double _timeout)
set the timeout for next readline() calls (negative value means: no timeout, wait for ever) ...
char const * GetLastErrorMessage(void)
return the last error message as string. The string returned will be overwritten by the next call to ...
int write(char const *ptr, int len=0)
Write data to a previously opened port.
int fd
the file descriptor of the RS232 port
cRS232(int _port, unsigned long _baudrate, double _timeout, char const *_device_format_string="/dev/ttyS%d")
#define USING_NAMESPACE_SDH
bool IsOpen(void)
Return true if port to RS232 is open.
int port
the RS232 portnumber to use
Interface of class #SDH::cRS232, a class to access serial RS232 port on cygwin/linux.
tcflag_t BaudrateToBaudrateCode(unsigned long baudrate)
Translate a baudrate given as unsigned long into a baudrate code for struct termios.
This file contains settings to make the SDHLibrary compile on differen systems:
Very simple class to measure elapsed time.
unsigned long baudrate
the baudrate in bit/s
Derived exception class for low-level RS232 related exceptions.
Class for short, fixed maximum length text messages.
long Elapsed_us(void) const
Return time in micro seconds elapsed between the time stored in the object and now.
cDBG dbg
A stream object to print colored debug messages.