#include <LxSerial.h>
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 |
Definition at line 24 of file LxSerial.h.
enum LxSerial::PortSpeed |
Definition at line 33 of file LxSerial.h.
enum LxSerial::PortType |
Definition at line 27 of file LxSerial.h.
Definition at line 24 of file LxSerial.cpp.
Definition at line 455 of file LxSerial.cpp.
void LxSerial::flush_buffer | ( | ) |
Definition at line 450 of file LxSerial.cpp.
std::string & LxSerial::get_port_name | ( | ) |
Definition at line 34 of file LxSerial.cpp.
bool LxSerial::is_port_open | ( | ) |
Definition at line 211 of file LxSerial.cpp.
bool LxSerial::port_close | ( | ) |
Definition at line 286 of file LxSerial.cpp.
bool LxSerial::port_open | ( | const std::string & | portname, |
LxSerial::PortType | port_type | ||
) |
Definition at line 74 of file LxSerial.cpp.
int LxSerial::port_read | ( | unsigned char * | buffer, |
int | numBytes | ||
) | const |
Definition at line 306 of file LxSerial.cpp.
int LxSerial::port_read | ( | unsigned char * | buffer, |
int | numBytes, | ||
int | seconds, | ||
int | microseconds | ||
) |
Definition at line 320 of file LxSerial.cpp.
int LxSerial::port_write | ( | unsigned char * | buffer, |
int | numBytes | ||
) |
Definition at line 368 of file LxSerial.cpp.
void LxSerial::set_clear_echo | ( | bool | clear | ) |
Definition at line 280 of file LxSerial.cpp.
void LxSerial::set_port_type | ( | LxSerial::PortType | port_type | ) | [protected] |
Definition at line 39 of file LxSerial.cpp.
bool LxSerial::set_speed | ( | LxSerial::PortSpeed | baudrate | ) |
Definition at line 217 of file LxSerial.cpp.
bool LxSerial::set_speed_int | ( | const int | baudrate | ) |
Definition at line 234 of file LxSerial.cpp.
bool LxSerial::wait_for_input | ( | int * | seconds, |
int * | microseconds | ||
) | [protected] |
Definition at line 354 of file LxSerial.cpp.
bool LxSerial::b_clear_echo [protected] |
Definition at line 79 of file LxSerial.h.
bool LxSerial::b_hw_flow_control [protected] |
Definition at line 81 of file LxSerial.h.
bool LxSerial::b_rts [protected] |
Definition at line 80 of file LxSerial.h.
bool LxSerial::b_socket [protected] |
Definition at line 82 of file LxSerial.h.
const int LxSerial::COLLISION_DETECT_ERROR = -2 [static] |
Definition at line 66 of file LxSerial.h.
const int LxSerial::COLLISION_WAIT_TIME_USEC = 10000 [static] |
Definition at line 70 of file LxSerial.h.
const int LxSerial::ECHO_TIMEOUT_ERROR = -3 [static] |
Definition at line 67 of file LxSerial.h.
const int LxSerial::ECHO_WAIT_TIME_SEC = 1 [static] |
Definition at line 71 of file LxSerial.h.
const int LxSerial::ECHO_WAIT_TIME_USEC = 0 [static] |
Definition at line 72 of file LxSerial.h.
int LxSerial::hPort [protected] |
Definition at line 76 of file LxSerial.h.
termios LxSerial::old_options [protected] |
Definition at line 83 of file LxSerial.h.
termios LxSerial::options [protected] |
Definition at line 83 of file LxSerial.h.
const int LxSerial::READ_ERROR = -1 [static] |
Definition at line 65 of file LxSerial.h.
std::string LxSerial::s_port_name [protected] |
Definition at line 77 of file LxSerial.h.
const int LxSerial::WAIT_FOR_DATA_DSEC = 5 [static] |
Definition at line 73 of file LxSerial.h.