LxSerial.h
Go to the documentation of this file.
00001 //============================================================================
00002 // Name        : LxSerial.cpp
00003 // Author      : Eelko van Breda,www.dbl.tudelft.nl
00004 // Version     : 0.1
00005 // Copyright   : Copyright (c) 2008 LGPL
00006 // Description : serial communicatin class linux
00007 //============================================================================
00008 
00009 #ifndef LXSERIAL_H_
00010 #define LXSERIAL_H_
00011 //#define __DBG__
00012 
00013 #include <fcntl.h>                                                                                                                              /* fileio */
00014 #include <termios.h>                                                                                                                    /* terminal i/o system, talks to /dev/tty* ports  */
00015 #include <unistd.h>                                                                                                                             /* Read function */
00016 #include <sys/ioctl.h>                                                                                                                  /* ioctl function */
00017 #include <iostream>
00018 #include <assert.h>
00019 #include <stdint.h>
00020 #include <string.h>
00021 
00022 #define INVALID_DEVICE_HANDLE           -1
00023 
00024 class LxSerial
00025 {
00026         public:
00027                 enum PortType {         RS232,                                                                                                  // Normal RS232
00028                                                         RS485_EXAR,                                                                                             // EXAR XR16C2850
00029                                                         RS485_FTDI,                                                                                             // FTDI FT232RL in 485 mode
00030                                                         RS485_SMSC,                                                                                             // SMSC SCH311X RS-485 mode (Versalogic Sidewinder board)
00031                                                         TCP
00032                 };
00033                 enum PortSpeed {        S50                     =       B50,                                                                    // Baudrate to use for the port --> see termios.h
00034                                                         S75                     =       B75,
00035                                                         S110            =       B110,
00036                                                         S134            =       B134,
00037                                                         S150            =       B150,
00038                                                         S200            =       B200,
00039                                                         S300            =       B300,
00040                                                         S600            =       B600,
00041                                                         S1200           =       B1200,
00042                                                         S1800           =       B1800,
00043                                                         S2400           =       B2400,
00044                                                         S4800           =       B4800,
00045                                                         S9600           =       B9600,
00046                                                         S19200          =       B19200,
00047                                                         S38400          =       B38400,
00048                                                         S57600          =       B57600,
00049                                                         S115200         =       B115200,
00050                                                         S230400         =       B230400,
00051                                                         S460800         =       B460800,
00052                                                         S500000         =       B500000,
00053                                                         S576000         =       B576000,
00054                                                         S921600         =       B921600,
00055                                                         S1000000        =       B1000000,
00056                                                         S1152000        =       B1152000,
00057                                                         S1500000        =       B1500000,
00058                                                         S2000000        =       B2000000,
00059                                                         S2500000        =       B2500000,
00060                                                         S3000000        =       B3000000,
00061                                                         S3500000        =       B3500000,
00062                                                         S4000000        =       B4000000
00063                 };
00064                 /*return values*/
00065                 static const int READ_ERROR                             =       -1;
00066                 static const int COLLISION_DETECT_ERROR         =       -2;
00067                 static const int ECHO_TIMEOUT_ERROR                     =       -3;
00068 
00069                 /*magic numbers*/
00070                 static const int COLLISION_WAIT_TIME_USEC       =       10000;                                                  // microseconds
00071                 static const int ECHO_WAIT_TIME_SEC                     =       1;                                                              // seconds
00072                 static const int ECHO_WAIT_TIME_USEC            =       0;                                                      // microseconds
00073                 static const int WAIT_FOR_DATA_DSEC                     =       5;                                                              //
00074 
00075         protected:
00076                 int                     hPort;                                                                                                                  // file handle to the port
00077                 std::string             s_port_name;                                                                                                    // name of the port that was opened
00078 //              bool                    b_initialised;                                                                                                  //
00079                 bool                    b_clear_echo;                                                                                                   // read sended characters from Rx when true
00080                 bool                    b_rts;                                                                                                                  // this boolean must be set to enforce setting the RTS signal without hardware contol enabled
00081                 bool                    b_hw_flow_control;                                                                                              //
00082                 bool                    b_socket;
00083                 termios                 options, old_options;                                                                                   //
00084                 bool                    wait_for_input(int *seconds, int *microseconds);                                        // private member function to wait for port. the time variables are modified after return to reflect the time not slept
00085                 void                    set_port_type(LxSerial::PortType port_type);
00086 
00087         public:
00088                         LxSerial();
00089                          ~LxSerial();
00090                 bool    port_open(const std::string& portname, LxSerial::PortType port_type);   // open serial port. If overridden, make sure you set s_port_name!!
00091                 bool    is_port_open();
00092                 std::string&    get_port_name();
00093                 bool    set_speed(LxSerial::PortSpeed baudrate );                                               // enumerated
00094                 bool    set_speed_int(const int baudrate);      // Set speed by integer value directly - UNPROTECTED!
00095                 void    set_clear_echo(bool clear);                                                                             // clear echoed charackters from input and detect collisions on write
00096                 bool    port_close();
00097                 int     port_read(unsigned char* buffer, int numBytes) const;
00098                 int     port_read(unsigned char* buffer, int numBytes, int seconds, int microseconds);
00099                 int     port_write(unsigned char* buffer, int numBytes);
00100                 void    flush_buffer();                                                                                                 // flush input and output buffers
00101 
00102 };
00103 
00104 
00105 #endif /*LXSERIAL_H_*/


shared_serial
Author(s): Wouter Caarls
autogenerated on Sun Jan 5 2014 11:06:47