00001
00002
00003
00004
00005
00006
00007
00008
00009 #ifndef LXSERIAL_H_
00010 #define LXSERIAL_H_
00011
00012
00013 #include <fcntl.h>
00014 #include <termios.h>
00015 #include <unistd.h>
00016 #include <sys/ioctl.h>
00017 #include <iostream>
00018 #include <assert.h>
00019 #include <stdint.h>
00020 #include <string.h>
00021
00022 #ifdef __APPLE__
00023 #include <sys/ioctl.h>
00024
00025 #ifndef IOSSIOSPEED
00026 #define IOSSIOSPEED _IOW('T', 2, speed_t)
00027 #endif
00028 #endif
00029
00030 #define INVALID_DEVICE_HANDLE -1
00031
00032 class LxSerial
00033 {
00034 public:
00035 enum PortType { RS232,
00036 RS485_EXAR,
00037 RS485_FTDI,
00038 RS485_SMSC
00039 };
00040
00041 #ifdef __APPLE__
00042 enum PortSpeed { S50 = 50,
00043 S75 = 75,
00044 S110 = 110,
00045 S134 = 134,
00046 S150 = 150,
00047 S200 = 200,
00048 S300 = 300,
00049 S600 = 600,
00050 S1200 = 1200,
00051 S1800 = 1800,
00052 S2400 = 2400,
00053 S4800 = 4800,
00054 S9600 = 9600,
00055 S19200 = 19200,
00056 S38400 = 38400,
00057 S57600 = 57600,
00058 S115200 = 115200,
00059 S230400 = 230400,
00060 S460800 = 460800,
00061 S500000 = 500000,
00062 S576000 = 576000,
00063 S921600 = 921600,
00064 S1000000 = 1000000,
00065 S1152000 = 1152000,
00066 S1500000 = 1500000,
00067 S2000000 = 2000000,
00068 S2500000 = 2500000,
00069 S3000000 = 3000000,
00070 S3500000 = 3500000,
00071 S4000000 = 4000000
00072 };
00073 #else
00074 enum PortSpeed { S50 = B50,
00075 S75 = B75,
00076 S110 = B110,
00077 S134 = B134,
00078 S150 = B150,
00079 S200 = B200,
00080 S300 = B300,
00081 S600 = B600,
00082 S1200 = B1200,
00083 S1800 = B1800,
00084 S2400 = B2400,
00085 S4800 = B4800,
00086 S9600 = B9600,
00087 S19200 = B19200,
00088 S38400 = B38400,
00089 S57600 = B57600,
00090 S115200 = B115200,
00091 S230400 = B230400,
00092 S460800 = B460800,
00093 S500000 = B500000,
00094 S576000 = B576000,
00095 S921600 = B921600,
00096 S1000000 = B1000000,
00097 S1152000 = B1152000,
00098 S1500000 = B1500000,
00099 S2000000 = B2000000,
00100 S2500000 = B2500000,
00101 S3000000 = B3000000,
00102 S3500000 = B3500000,
00103 S4000000 = B4000000
00104 };
00105 #endif
00106
00107 static const int READ_ERROR = -1;
00108 static const int COLLISION_DETECT_ERROR = -2;
00109 static const int ECHO_TIMEOUT_ERROR = -3;
00110
00111
00112 static const int COLLISION_WAIT_TIME_USEC = 10000;
00113 static const int ECHO_WAIT_TIME_SEC = 1;
00114 static const int ECHO_WAIT_TIME_USEC = 0;
00115 static const int WAIT_FOR_DATA_DSEC = 5;
00116
00117 protected:
00118 int hPort;
00119 std::string s_port_name;
00120
00121 bool b_clear_echo;
00122 bool b_rts;
00123 bool b_hw_flow_control;
00124 termios options, old_options;
00125 bool wait_for_input(int *seconds, int *microseconds);
00126 void set_port_type(LxSerial::PortType port_type);
00127
00128 public:
00129 LxSerial();
00130 virtual ~LxSerial();
00131 virtual bool port_open(const std::string& portname, LxSerial::PortType port_type);
00132 virtual bool is_port_open();
00133 std::string& get_port_name();
00134 virtual bool set_speed(LxSerial::PortSpeed baudrate );
00135 virtual bool set_speed_int(const int baudrate);
00136 void set_clear_echo(bool clear);
00137 virtual bool port_close();
00138 virtual int port_read(unsigned char* buffer, int numBytes) const;
00139 virtual int port_read(unsigned char* buffer, int numBytes, int seconds, int microseconds);
00140 virtual int port_write(unsigned char* buffer, int numBytes);
00141 virtual void flush_buffer();
00142
00143 };
00144
00145
00146 #endif