Classes | Public Member Functions | Private Member Functions | Private Attributes
serial::Serial Class Reference

#include <serial.h>

List of all members.

Classes

class  ScopedReadLock
class  ScopedWriteLock
class  SerialImpl

Public Member Functions

size_t available ()
void close ()
void flush ()
void flushInput ()
void flushOutput ()
uint32_t getBaudrate () const
bytesize_t getBytesize () const
bool getCD ()
bool getCTS ()
bool getDSR ()
flowcontrol_t getFlowcontrol () const
parity_t getParity () const
std::string getPort () const
bool getRI ()
stopbits_t getStopbits () const
Timeout getTimeout () const
bool isOpen () const
void open ()
size_t read (uint8_t *buffer, size_t size)
size_t read (std::vector< uint8_t > &buffer, size_t size=1)
size_t read (std::string &buffer, size_t size=1)
std::string read (size_t size=1)
size_t readline (std::string &buffer, size_t size=65536, std::string eol="\n")
std::string readline (size_t size=65536, std::string eol="\n")
std::vector< std::string > readlines (size_t size=65536, std::string eol="\n")
void sendBreak (int duration)
 Serial (const std::string &port="", uint32_t baudrate=9600, Timeout timeout=Timeout(), bytesize_t bytesize=eightbits, parity_t parity=parity_none, stopbits_t stopbits=stopbits_one, flowcontrol_t flowcontrol=flowcontrol_none)
void setBaudrate (uint32_t baudrate)
void setBreak (bool level=true)
void setBytesize (bytesize_t bytesize)
void setDTR (bool level=true)
void setFlowcontrol (flowcontrol_t flowcontrol)
void setParity (parity_t parity)
void setPort (const std::string &port)
void setRTS (bool level=true)
void setStopbits (stopbits_t stopbits)
void setTimeout (Timeout &timeout)
void setTimeout (uint32_t inter_byte_timeout, uint32_t read_timeout_constant, uint32_t read_timeout_multiplier, uint32_t write_timeout_constant, uint32_t write_timeout_multiplier)
void waitByteTimes (size_t count)
bool waitForChange ()
bool waitReadable ()
size_t write (const uint8_t *data, size_t size)
size_t write (const std::vector< uint8_t > &data)
size_t write (const std::string &data)
virtual ~Serial ()

Private Member Functions

Serialoperator= (const Serial &)
size_t read_ (uint8_t *buffer, size_t size)
 Serial (const Serial &)
size_t write_ (const uint8_t *data, size_t length)

Private Attributes

SerialImplpimpl_

Detailed Description

Class that provides a portable serial port interface.

Definition at line 145 of file serial.h.


Constructor & Destructor Documentation

serial::Serial::Serial ( const std::string &  port = "",
uint32_t  baudrate = 9600,
Timeout  timeout = Timeout(),
bytesize_t  bytesize = eightbits,
parity_t  parity = parity_none,
stopbits_t  stopbits = stopbits_one,
flowcontrol_t  flowcontrol = flowcontrol_none 
)

Creates a Serial object and opens the port if a port is specified, otherwise it remains closed until serial::Serial::open is called.

Parameters:
portA std::string containing the address of the serial port, which would be something like 'COM1' on Windows and '/dev/ttyS0' on Linux.
baudrateAn unsigned 32-bit integer that represents the baudrate
timeoutA serial::Timeout struct that defines the timeout conditions for the serial port.
See also:
serial::Timeout
Parameters:
bytesizeSize of each byte in the serial transmission of data, default is eightbits, possible values are: fivebits, sixbits, sevenbits, eightbits
parityMethod of parity, default is parity_none, possible values are: parity_none, parity_odd, parity_even
stopbitsNumber of stop bits used, default is stopbits_one, possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
flowcontrolType of flowcontrol used, default is flowcontrol_none, possible values are: flowcontrol_none, flowcontrol_software, flowcontrol_hardware
Exceptions:
serial::PortNotOpenedException
serial::IOException
std::invalid_argument
Serial::~Serial ( ) [virtual]

Destructor

Definition at line 75 of file serial.cc.

serial::Serial::Serial ( const Serial ) [private]

Member Function Documentation

size_t Serial::available ( )

Return the number of characters in the buffer.

Definition at line 99 of file serial.cc.

void Serial::close ( )

Closes the serial port.

Definition at line 87 of file serial.cc.

void Serial::flush ( )

Flush the input and output buffers

Definition at line 352 of file serial.cc.

Flush only the input buffer

Definition at line 359 of file serial.cc.

Flush only the output buffer

Definition at line 365 of file serial.cc.

uint32_t Serial::getBaudrate ( ) const

Gets the baudrate for the serial port.

Returns:
An integer that sets the baud rate for the serial port.
See also:
Serial::setBaudrate
Exceptions:
InvalidConfigurationException

Definition at line 299 of file serial.cc.

Gets the bytesize for the serial port.

See also:
Serial::setBytesize
Exceptions:
InvalidConfigurationException

Definition at line 311 of file serial.cc.

bool Serial::getCD ( )

Returns the current status of the CD line.

Definition at line 411 of file serial.cc.

bool Serial::getCTS ( )

Returns the current status of the CTS line.

Definition at line 396 of file serial.cc.

bool Serial::getDSR ( )

Returns the current status of the DSR line.

Definition at line 401 of file serial.cc.

Gets the flow control for the serial port.

See also:
Serial::setFlowcontrol
Exceptions:
InvalidConfigurationException

Definition at line 347 of file serial.cc.

Gets the parity for the serial port.

See also:
Serial::setParity
Exceptions:
InvalidConfigurationException

Definition at line 323 of file serial.cc.

string Serial::getPort ( ) const

Gets the serial port identifier.

See also:
Serial::setPort
Exceptions:
InvalidConfigurationException

Definition at line 276 of file serial.cc.

bool Serial::getRI ( )

Returns the current status of the RI line.

Definition at line 406 of file serial.cc.

Gets the stopbits for the serial port.

See also:
Serial::setStopbits
Exceptions:
InvalidConfigurationException

Definition at line 335 of file serial.cc.

Gets the timeout for reads in seconds.

Returns:
A Timeout struct containing the inter_byte_timeout, and read and write timeout constants and multipliers.
See also:
Serial::setTimeout

Definition at line 288 of file serial.cc.

bool Serial::isOpen ( ) const

Gets the open status of the serial port.

Returns:
Returns true if the port is open, false otherwise.

Definition at line 93 of file serial.cc.

void Serial::open ( )

Opens the serial port as long as the port is set and the port isn't already open.

If the port is provided to the constructor then an explicit call to open is not needed.

See also:
Serial::Serial
Exceptions:
std::invalid_argument
serial::SerialException
serial::IOException

Definition at line 81 of file serial.cc.

Serial& serial::Serial::operator= ( const Serial ) [private]
size_t Serial::read ( uint8_t *  buffer,
size_t  size 
)

Read a given amount of bytes from the serial port into a given buffer.

The read function will return in one of three cases: * The number of requested bytes was read. * In this case the number of bytes requested will match the size_t returned by read. * A timeout occurred, in this case the number of bytes read will not match the amount requested, but no exception will be thrown. One of two possible timeouts occurred: * The inter byte timeout expired, this means that number of milliseconds elapsed between receiving bytes from the serial port exceeded the inter byte timeout. * The total timeout expired, which is calculated by multiplying the read timeout multiplier by the number of requested bytes and then added to the read timeout constant. If that total number of milliseconds elapses after the initial call to read a timeout will occur. * An exception occurred, in this case an actual exception will be thrown.

Parameters:
bufferAn uint8_t array of at least the requested size.
sizeA size_t defining how many bytes to be read.
Returns:
A size_t representing the number of bytes read as a result of the call to read.

Definition at line 124 of file serial.cc.

size_t Serial::read ( std::vector< uint8_t > &  buffer,
size_t  size = 1 
)

Read a given amount of bytes from the serial port into a give buffer.

Parameters:
bufferA reference to a std::vector of uint8_t.
sizeA size_t defining how many bytes to be read.
Returns:
A size_t representing the number of bytes read as a result of the call to read.

Definition at line 131 of file serial.cc.

size_t Serial::read ( std::string &  buffer,
size_t  size = 1 
)

Read a given amount of bytes from the serial port into a give buffer.

Parameters:
bufferA reference to a std::string.
sizeA size_t defining how many bytes to be read.
Returns:
A size_t representing the number of bytes read as a result of the call to read.

Definition at line 142 of file serial.cc.

string Serial::read ( size_t  size = 1)

Read a given amount of bytes from the serial port and return a string containing the data.

Parameters:
sizeA size_t defining how many bytes to be read.
Returns:
A std::string containing the data read from the port.

Definition at line 153 of file serial.cc.

size_t Serial::read_ ( uint8_t *  buffer,
size_t  size 
) [private]

Definition at line 118 of file serial.cc.

size_t serial::Serial::readline ( std::string &  buffer,
size_t  size = 65536,
std::string  eol = "\n" 
)

Reads in a line or until a given delimiter has been processed.

Reads from the serial port until a single line has been read.

Parameters:
bufferA std::string reference used to store the data.
sizeA maximum length of a line, defaults to 65536 (2^16)
eolA string to match against for the EOL.
Returns:
A size_t representing the number of bytes read.
std::string serial::Serial::readline ( size_t  size = 65536,
std::string  eol = "\n" 
)

Reads in a line or until a given delimiter has been processed.

Reads from the serial port until a single line has been read.

Parameters:
sizeA maximum length of a line, defaults to 65536 (2^16)
eolA string to match against for the EOL.
Returns:
A std::string containing the line.
vector< string > Serial::readlines ( size_t  size = 65536,
std::string  eol = "\n" 
)

Reads in multiple lines until the serial port times out.

This requires a timeout > 0 before it can be run. It will read until a timeout occurs and return a list of strings.

Parameters:
sizeA maximum length of combined lines, defaults to 65536 (2^16)
eolA string to match against for the EOL.
Returns:
A vector<string> containing the lines.

Definition at line 196 of file serial.cc.

void Serial::sendBreak ( int  duration)

Sends the RS-232 break signal. See tcsendbreak(3).

Definition at line 371 of file serial.cc.

void Serial::setBaudrate ( uint32_t  baudrate)

Sets the baudrate for the serial port.

Possible baudrates depends on the system but some safe baudrates include: 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000, 57600, 115200 Some other baudrates that are supported by some comports: 128000, 153600, 230400, 256000, 460800, 921600

Parameters:
baudrateAn integer that sets the baud rate for the serial port.
Exceptions:
InvalidConfigurationException

Definition at line 293 of file serial.cc.

void Serial::setBreak ( bool  level = true)

Set the break condition to a given level. Defaults to true.

Definition at line 376 of file serial.cc.

void Serial::setBytesize ( bytesize_t  bytesize)

Sets the bytesize for the serial port.

Parameters:
bytesizeSize of each byte in the serial transmission of data, default is eightbits, possible values are: fivebits, sixbits, sevenbits, eightbits
Exceptions:
InvalidConfigurationException

Definition at line 305 of file serial.cc.

void Serial::setDTR ( bool  level = true)

Set the DTR handshaking line to the given level. Defaults to true.

Definition at line 386 of file serial.cc.

void Serial::setFlowcontrol ( flowcontrol_t  flowcontrol)

Sets the flow control for the serial port.

Parameters:
flowcontrolType of flowcontrol used, default is flowcontrol_none, possible values are: flowcontrol_none, flowcontrol_software, flowcontrol_hardware
Exceptions:
InvalidConfigurationException

Definition at line 341 of file serial.cc.

void Serial::setParity ( parity_t  parity)

Sets the parity for the serial port.

Parameters:
parityMethod of parity, default is parity_none, possible values are: parity_none, parity_odd, parity_even
Exceptions:
InvalidConfigurationException

Definition at line 317 of file serial.cc.

void Serial::setPort ( const std::string &  port)

Sets the serial port identifier.

Parameters:
portA const std::string reference containing the address of the serial port, which would be something like 'COM1' on Windows and '/dev/ttyS0' on Linux.
Exceptions:
InvalidConfigurationException

Definition at line 265 of file serial.cc.

void Serial::setRTS ( bool  level = true)

Set the RTS handshaking line to the given level. Defaults to true.

Definition at line 381 of file serial.cc.

void Serial::setStopbits ( stopbits_t  stopbits)

Sets the stopbits for the serial port.

Parameters:
stopbitsNumber of stop bits used, default is stopbits_one, possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
Exceptions:
InvalidConfigurationException

Definition at line 329 of file serial.cc.

void Serial::setTimeout ( serial::Timeout timeout)

Sets the timeout for reads and writes using the Timeout struct.

There are two timeout conditions described here: * The inter byte timeout: * The inter_byte_timeout component of serial::Timeout defines the maximum amount of time, in milliseconds, between receiving bytes on the serial port that can pass before a timeout occurs. Setting this to zero will prevent inter byte timeouts from occurring. * Total time timeout: * The constant and multiplier component of this timeout condition, for both read and write, are defined in serial::Timeout. This timeout occurs if the total time since the read or write call was made exceeds the specified time in milliseconds. * The limit is defined by multiplying the multiplier component by the number of requested bytes and adding that product to the constant component. In this way if you want a read call, for example, to timeout after exactly one second regardless of the number of bytes you asked for then set the read_timeout_constant component of serial::Timeout to 1000 and the read_timeout_multiplier to zero. This timeout condition can be used in conjunction with the inter byte timeout condition with out any problems, timeout will simply occur when one of the two timeout conditions is met. This allows users to have maximum control over the trade-off between responsiveness and efficiency.

Read and write functions will return in one of three cases. When the reading or writing is complete, when a timeout occurs, or when an exception occurs.

Parameters:
timeoutA serial::Timeout struct containing the inter byte timeout, and the read and write timeout constants and multipliers.
See also:
serial::Timeout

Definition at line 282 of file serial.cc.

void serial::Serial::setTimeout ( uint32_t  inter_byte_timeout,
uint32_t  read_timeout_constant,
uint32_t  read_timeout_multiplier,
uint32_t  write_timeout_constant,
uint32_t  write_timeout_multiplier 
) [inline]

Sets the timeout for reads and writes.

Definition at line 428 of file serial.h.

void Serial::waitByteTimes ( size_t  count)

Block for a period of time corresponding to the transmission time of count characters at present serial settings. This may be used in con- junction with waitReadable to read larger blocks of data from the port.

Definition at line 112 of file serial.cc.

Blocks until CTS, DSR, RI, CD changes or something interrupts it.

Can throw an exception if an error occurs while waiting. You can check the status of CTS, DSR, RI, and CD once this returns. Uses TIOCMIWAIT via ioctl if available (mostly only on Linux) with a resolution of less than +-1ms and as good as +-0.2ms. Otherwise a polling method is used which can give +-2ms.

Returns:
Returns true if one of the lines changed, false if something else occurred.
Exceptions:
SerialException

Definition at line 391 of file serial.cc.

Block until there is serial data to read or read_timeout_constant number of milliseconds have elapsed. The return value is true when the function exits with the port in a readable state, false otherwise (due to timeout or select interruption).

Definition at line 105 of file serial.cc.

size_t Serial::write ( const uint8_t *  data,
size_t  size 
)

Write a string to the serial port.

Parameters:
dataA const reference containing the data to be written to the serial port.
sizeA size_t that indicates how many bytes should be written from the given data buffer.
Returns:
A size_t representing the number of bytes actually written to the serial port.

Definition at line 252 of file serial.cc.

size_t Serial::write ( const std::vector< uint8_t > &  data)

Write a string to the serial port.

Parameters:
dataA const reference containing the data to be written to the serial port.
Returns:
A size_t representing the number of bytes actually written to the serial port.

Definition at line 245 of file serial.cc.

size_t serial::Serial::write ( const std::string &  data)

Write a string to the serial port.

Parameters:
dataA const reference containing the data to be written to the serial port.
Returns:
A size_t representing the number of bytes actually written to the serial port.
size_t Serial::write_ ( const uint8_t *  data,
size_t  length 
) [private]

Definition at line 259 of file serial.cc.


Member Data Documentation

Definition at line 619 of file serial.h.


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


serial
Author(s): William Woodall , John Harrison
autogenerated on Mon Oct 6 2014 07:34:37