Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
LxSerial Class Reference

#include <LxSerial.h>

List of all members.

Public Types

enum  PortSpeed {
  S50 = B50, S75 = B75, S110 = B110, S134 = B134,
  S150 = B150, S200 = B200, S300 = B300, S600 = B600,
  S1200 = B1200, S1800 = B1800, S2400 = B2400, S4800 = B4800,
  S9600 = B9600, S19200 = B19200, S38400 = B38400, S57600 = B57600,
  S115200 = B115200, S230400 = B230400, S460800 = B460800, S500000 = B500000,
  S576000 = B576000, S921600 = B921600, S1000000 = B1000000, S1152000 = B1152000,
  S1500000 = B1500000, S2000000 = B2000000, S2500000 = B2500000, S3000000 = B3000000,
  S3500000 = B3500000, S4000000 = B4000000
}
enum  PortType {
  RS232, RS485_EXAR, RS485_FTDI, RS485_SMSC,
  TCP
}

Public Member Functions

void flush_buffer ()
std::string & get_port_name ()
bool is_port_open ()
 LxSerial ()
bool port_close ()
bool port_open (const std::string &portname, LxSerial::PortType port_type)
int port_read (unsigned char *buffer, int numBytes) const
int port_read (unsigned char *buffer, int numBytes, int seconds, int microseconds)
int port_write (unsigned char *buffer, int numBytes)
void set_clear_echo (bool clear)
bool set_speed (LxSerial::PortSpeed baudrate)
bool set_speed_int (const int baudrate)
 ~LxSerial ()

Static Public Attributes

static const int COLLISION_DETECT_ERROR = -2
static const int COLLISION_WAIT_TIME_USEC = 10000
static const int ECHO_TIMEOUT_ERROR = -3
static const int ECHO_WAIT_TIME_SEC = 1
static const int ECHO_WAIT_TIME_USEC = 0
static const int READ_ERROR = -1
static const int WAIT_FOR_DATA_DSEC = 5

Protected Member Functions

void set_port_type (LxSerial::PortType port_type)
bool wait_for_input (int *seconds, int *microseconds)

Protected Attributes

bool b_clear_echo
bool b_hw_flow_control
bool b_rts
bool b_socket
int hPort
termios old_options
termios options
std::string s_port_name

Detailed Description

Definition at line 30 of file LxSerial.h.


Member Enumeration Documentation

Enumerator:
S50 
S75 
S110 
S134 
S150 
S200 
S300 
S600 
S1200 
S1800 
S2400 
S4800 
S9600 
S19200 
S38400 
S57600 
S115200 
S230400 
S460800 
S500000 
S576000 
S921600 
S1000000 
S1152000 
S1500000 
S2000000 
S2500000 
S3000000 
S3500000 
S4000000 

Definition at line 72 of file LxSerial.h.

Enumerator:
RS232 
RS485_EXAR 
RS485_FTDI 
RS485_SMSC 
TCP 

Definition at line 33 of file LxSerial.h.


Constructor & Destructor Documentation

Definition at line 29 of file LxSerial.cpp.

Definition at line 469 of file LxSerial.cpp.


Member Function Documentation

Definition at line 464 of file LxSerial.cpp.

std::string & LxSerial::get_port_name ( )

Definition at line 39 of file LxSerial.cpp.

Definition at line 216 of file LxSerial.cpp.

Definition at line 300 of file LxSerial.cpp.

bool LxSerial::port_open ( const std::string &  portname,
LxSerial::PortType  port_type 
)

Definition at line 79 of file LxSerial.cpp.

int LxSerial::port_read ( unsigned char *  buffer,
int  numBytes 
) const

Definition at line 320 of file LxSerial.cpp.

int LxSerial::port_read ( unsigned char *  buffer,
int  numBytes,
int  seconds,
int  microseconds 
)

Definition at line 334 of file LxSerial.cpp.

int LxSerial::port_write ( unsigned char *  buffer,
int  numBytes 
)

Definition at line 382 of file LxSerial.cpp.

void LxSerial::set_clear_echo ( bool  clear)

Definition at line 294 of file LxSerial.cpp.

void LxSerial::set_port_type ( LxSerial::PortType  port_type) [protected]

Definition at line 44 of file LxSerial.cpp.

Definition at line 222 of file LxSerial.cpp.

bool LxSerial::set_speed_int ( const int  baudrate)

Definition at line 248 of file LxSerial.cpp.

bool LxSerial::wait_for_input ( int *  seconds,
int *  microseconds 
) [protected]

Definition at line 368 of file LxSerial.cpp.


Member Data Documentation

bool LxSerial::b_clear_echo [protected]

Definition at line 119 of file LxSerial.h.

bool LxSerial::b_hw_flow_control [protected]

Definition at line 121 of file LxSerial.h.

bool LxSerial::b_rts [protected]

Definition at line 120 of file LxSerial.h.

bool LxSerial::b_socket [protected]

Definition at line 122 of file LxSerial.h.

const int LxSerial::COLLISION_DETECT_ERROR = -2 [static]

Definition at line 106 of file LxSerial.h.

const int LxSerial::COLLISION_WAIT_TIME_USEC = 10000 [static]

Definition at line 110 of file LxSerial.h.

const int LxSerial::ECHO_TIMEOUT_ERROR = -3 [static]

Definition at line 107 of file LxSerial.h.

const int LxSerial::ECHO_WAIT_TIME_SEC = 1 [static]

Definition at line 111 of file LxSerial.h.

const int LxSerial::ECHO_WAIT_TIME_USEC = 0 [static]

Definition at line 112 of file LxSerial.h.

int LxSerial::hPort [protected]

Definition at line 116 of file LxSerial.h.

termios LxSerial::old_options [protected]

Definition at line 123 of file LxSerial.h.

termios LxSerial::options [protected]

Definition at line 123 of file LxSerial.h.

const int LxSerial::READ_ERROR = -1 [static]

Definition at line 105 of file LxSerial.h.

std::string LxSerial::s_port_name [protected]

Definition at line 117 of file LxSerial.h.

const int LxSerial::WAIT_FOR_DATA_DSEC = 5 [static]

Definition at line 113 of file LxSerial.h.


The documentation for this class was generated from the following files:


shared_serial
Author(s): Wouter Caarls
autogenerated on Fri Aug 28 2015 13:06:29