Main MRPT website > C++ reference
MRPT logo
List of all members | Public Types | Public Member Functions | Protected Attributes | Friends
mrpt::hwdrivers::CSerialPort Class Referenceabstract

Detailed Description

A communications serial port built as an implementation of a utils::CStream.

On communication errors (eg. the given port number does not exist, timeouts,...), most of the methods will raise an exception of the class "std::exception"

The serial port to open is passed in the constructor in the form of a string description, which is platform dependent.

In windows they are numbered "COM1"-"COM4" and "\\.\COMXXX" for numbers above. It is recomended to always use the prefix "\\.\" despite the actual port number.

In Linux the name must refer to the device, for example: "ttyUSB0","ttyS0". If the name string does not start with "/" (an absolute path), the constructor will assume the prefix "/dev/".

History:

Todo:
Add the internal buffer to the Windows implementation also

Definition at line 47 of file CSerialPort.h.

#include <mrpt/hwdrivers/CSerialPort.h>

Inheritance diagram for mrpt::hwdrivers::CSerialPort:
Inheritance graph
[legend]

Public Types

enum  TSeekOrigin { sFromBeginning = 0, sFromCurrent = 1, sFromEnd = 2 }
 Used in CStream::Seek. More...
 

Public Member Functions

 CSerialPort (const std::string &portName, bool openNow=true)
 Constructor. More...
 
 CSerialPort ()
 Default constructor: it does not open any port - later you must call "setSerialPortName" and then "open". More...
 
virtual ~CSerialPort ()
 Destructor. More...
 
void setSerialPortName (const std::string &COM_name)
 Sets the serial port to open (it is an error to try to change this while open yet). More...
 
void open ()
 Open the port. More...
 
void open (const std::string &COM_name)
 Open the given serial port. More...
 
void close ()
 Close the port. More...
 
bool isOpen ()
 Returns if port has been correctly open. More...
 
void purgeBuffers ()
 Purge tx and rx buffers. More...
 
void setConfig (int baudRate, int parity=0, int bits=8, int nStopBits=1, bool enableFlowControl=false)
 Changes the configuration of the port. More...
 
void setTimeouts (int ReadIntervalTimeout, int ReadTotalTimeoutMultiplier, int ReadTotalTimeoutConstant, int WriteTotalTimeoutMultiplier, int WriteTotalTimeoutConstant)
 Changes the timeouts of the port, in milliseconds. More...
 
size_t Read (void *Buffer, size_t Count)
 Implements the virtual method responsible for reading from the stream - Unlike CStream::ReadBuffer, this method will not raise an exception on zero bytes read, as long as there is not any fatal error in the communications. More...
 
std::string ReadString (const int total_timeout_ms=-1, bool *out_timeout=NULL, const char *eol_chars="\")
 Reads one text line from the serial port in POSIX "canonical mode". More...
 
size_t Write (const void *Buffer, size_t Count)
 Implements the virtual method responsible for writing to the stream. More...
 
uint64_t Seek (uint64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning)
 Introduces a pure virtual method for moving to a specified position in the streamed resource. More...
 
uint64_t getTotalBytesCount ()
 Returns the total amount of bytes in the stream. More...
 
uint64_t getPosition ()
 Method for getting the current cursor position, where 0 is the first byte and TotalBytesCount-1 the last one. More...
 
size_t ReadBuffer (void *Buffer, size_t Count)
 Reads a block of bytes from the stream into Buffer. More...
 
template<typename T >
size_t ReadBufferFixEndianness (T *ptr, size_t ElementCount)
 Reads a sequence of elemental datatypes, taking care of reordering their bytes from the MRPT stream standard (little endianness) to the format of the running architecture. More...
 
virtual size_t ReadBufferImmediate (void *Buffer, size_t Count)
 Reads a block of bytes from the stream into Buffer, and returns the amound of bytes actually read, without waiting for more extra bytes to arrive (just those already enqued in the stream). More...
 
void WriteBuffer (const void *Buffer, size_t Count)
 Writes a block of bytes to the stream from Buffer. More...
 
template<typename T >
void WriteBufferFixEndianness (const T *ptr, size_t ElementCount)
 Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running architecture to MRPT stream standard (little endianness). More...
 
size_t CopyFrom (CStream *Source, size_t Count)
 Copies a specified number of bytes from one stream to another. More...
 
virtual uint64_t Seek (uint64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning)=0
 Introduces a pure virtual method for moving to a specified position in the streamed resource. More...
 
void WriteObject (const CSerializable *o)
 Writes an object to the stream. More...
 
CSerializablePtr ReadObject ()
 Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object. More...
 
void ReadObject (CSerializable *existingObj)
 Reads an object from stream, where its class must be the same as the supplied object, where the loaded object will be stored in. More...
 
CStreamoperator<< (const CSerializablePtr &pObj)
 Write an object to a stream in the binary MRPT format. More...
 
CStreamoperator<< (const CSerializable &obj)
 Write an object to a stream in the binary MRPT format. More...
 
CStreamoperator>> (CSerializablePtr &pObj)
 
CStreamoperator>> (CSerializable &obj)
 
virtual int printf (const char *fmt,...) MRPT_printf_format_check(2
 Writes a string to the stream in a textual form. More...
 
template<typename T >
virtual int void printf_vector (const char *fmt, const std::vector< T > &V)
 Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element. More...
 
void sendMessage (const utils::CMessage &msg)
 Send a message to the device. More...
 
bool receiveMessage (utils::CMessage &msg)
 Tries to receive a message from the device. More...
 
bool getline (std::string &out_str)
 Reads from the stream until a '
' character is found ('' characters are ignored). More...
 

Protected Attributes

std::string m_serialName
 The complete name of the serial port device (i.e. More...
 
int m_baudRate
 
int m_totalTimeout_ms
 
int m_interBytesTimeout_ms
 
CTicTac m_timer
 Used only in ReadString. More...
 
int hCOM
 The file handle (-1: Not open) More...
 

Friends

class PosixSignalDispatcherImpl
 

Member Enumeration Documentation

◆ TSeekOrigin

Used in CStream::Seek.

Enumerator
sFromBeginning 
sFromCurrent 
sFromEnd 

Definition at line 41 of file CStream.h.

Constructor & Destructor Documentation

◆ CSerialPort() [1/2]

mrpt::hwdrivers::CSerialPort::CSerialPort ( const std::string &  portName,
bool  openNow = true 
)

Constructor.

Parameters
portNameThe serial port to open. See comments at the begining of this page.
openNowWhether to try to open the port now. If not selected, the port should be open later with "open()".

◆ CSerialPort() [2/2]

mrpt::hwdrivers::CSerialPort::CSerialPort ( )

Default constructor: it does not open any port - later you must call "setSerialPortName" and then "open".

◆ ~CSerialPort()

virtual mrpt::hwdrivers::CSerialPort::~CSerialPort ( )
virtual

Destructor.

Member Function Documentation

◆ close()

void mrpt::hwdrivers::CSerialPort::close ( )

Close the port.

If is already closed, results in no action.

Referenced by mrpt::hwdrivers::CRaePID::~CRaePID().

◆ CopyFrom()

size_t mrpt::utils::CStream::CopyFrom ( CStream Source,
size_t  Count 
)
inherited

Copies a specified number of bytes from one stream to another.

◆ getline()

bool mrpt::utils::CStream::getline ( std::string &  out_str)
inherited

Reads from the stream until a '
' character is found ('' characters are ignored).

Returns
false on EOF or any other read error.

◆ getPosition()

uint64_t mrpt::hwdrivers::CSerialPort::getPosition ( )
inlinevirtual

Method for getting the current cursor position, where 0 is the first byte and TotalBytesCount-1 the last one.

Implements mrpt::utils::CStream.

Definition at line 182 of file CSerialPort.h.

References MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ getTotalBytesCount()

uint64_t mrpt::hwdrivers::CSerialPort::getTotalBytesCount ( )
inlinevirtual

Returns the total amount of bytes in the stream.

Implements mrpt::utils::CStream.

Definition at line 173 of file CSerialPort.h.

References MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ isOpen()

bool mrpt::hwdrivers::CSerialPort::isOpen ( )

Returns if port has been correctly open.

◆ open() [1/2]

void mrpt::hwdrivers::CSerialPort::open ( )

Open the port.

If is already open results in no action.

Exceptions
std::exceptionOn communication errors

◆ open() [2/2]

void mrpt::hwdrivers::CSerialPort::open ( const std::string &  COM_name)
inline

Open the given serial port.

If it is already open and the name does not match, an exception is raised.

Exceptions
std::exceptionOn communication errors or a different serial port already open.

Definition at line 83 of file CSerialPort.h.

References THROW_EXCEPTION.

◆ operator<<() [1/2]

CStream& mrpt::utils::CStream::operator<< ( const CSerializablePtr pObj)
inherited

Write an object to a stream in the binary MRPT format.

◆ operator<<() [2/2]

CStream& mrpt::utils::CStream::operator<< ( const CSerializable obj)
inherited

Write an object to a stream in the binary MRPT format.

◆ operator>>() [1/2]

CStream& mrpt::utils::CStream::operator>> ( CSerializablePtr pObj)
inherited

◆ operator>>() [2/2]

CStream& mrpt::utils::CStream::operator>> ( CSerializable obj)
inherited

◆ printf()

virtual int mrpt::utils::CStream::printf ( const char *  fmt,
  ... 
)
virtualinherited

◆ printf_vector()

template<typename T >
virtual int void mrpt::utils::CStream::printf_vector ( const char *  fmt,
const std::vector< T > &  V 
)
inlineinherited

Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element.

Definition at line 200 of file CStream.h.

◆ purgeBuffers()

void mrpt::hwdrivers::CSerialPort::purgeBuffers ( )

Purge tx and rx buffers.

Exceptions
std::exceptionOn communication errors

◆ Read()

size_t mrpt::hwdrivers::CSerialPort::Read ( void *  Buffer,
size_t  Count 
)
virtual

Implements the virtual method responsible for reading from the stream - Unlike CStream::ReadBuffer, this method will not raise an exception on zero bytes read, as long as there is not any fatal error in the communications.

Exceptions
std::exceptionOn communication errors

Implements mrpt::utils::CStream.

◆ ReadBuffer()

size_t mrpt::utils::CStream::ReadBuffer ( void *  Buffer,
size_t  Count 
)
inherited

Reads a block of bytes from the stream into Buffer.

Exceptions
std::exceptionOn any error, or if ZERO bytes are read.
Returns
The amound of bytes actually read.
Note
This method is endianness-dependent.
See also
ReadBufferImmediate ; Important, see: ReadBufferFixEndianness,

◆ ReadBufferFixEndianness()

template<typename T >
size_t mrpt::utils::CStream::ReadBufferFixEndianness ( T *  ptr,
size_t  ElementCount 
)
inlineinherited

Reads a sequence of elemental datatypes, taking care of reordering their bytes from the MRPT stream standard (little endianness) to the format of the running architecture.

Parameters
ElementCountThe number of elements (not bytes) to read.
ptrA pointer to the first output element in an array (or std::vector<>, etc...).
Returns
The amound of bytes (not elements) actually read (under error situations, the last element may be invalid if the data stream abruptly ends). Example of usage:
uint32_t N;
s >> N;
vector<float> vec(N);
if (N)
s.ReadBufferFixEndianness<float>(&vec[0],N);
Exceptions
std::exceptionOn any error, or if ZERO bytes are read.
See also
ReadBufferFixEndianness, ReadBuffer

Definition at line 90 of file CStream.h.

References mrpt::mrpt::utils::reverseBytesInPlace().

Referenced by mrpt::math::operator>>().

◆ ReadBufferImmediate()

virtual size_t mrpt::utils::CStream::ReadBufferImmediate ( void *  Buffer,
size_t  Count 
)
inlinevirtualinherited

Reads a block of bytes from the stream into Buffer, and returns the amound of bytes actually read, without waiting for more extra bytes to arrive (just those already enqued in the stream).

Note that this method will fallback to ReadBuffer() in most CStream classes but in some hardware-related classes.

Exceptions
std::exceptionOn any error, or if ZERO bytes are read.

Reimplemented in mrpt::hwdrivers::CInterfaceFTDI.

Definition at line 108 of file CStream.h.

◆ ReadObject() [1/2]

CSerializablePtr mrpt::utils::CStream::ReadObject ( )
inherited

Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object.

Exceptions
std::exceptionOn I/O error or undefined class.
mrpt::utils::CExceptionEOFOn an End-Of-File condition found at a correct place: an EOF that abruptly finishes in the middle of one object raises a plain std::exception instead.

Referenced by mrpt::math::operator>>().

◆ ReadObject() [2/2]

void mrpt::utils::CStream::ReadObject ( CSerializable existingObj)
inherited

Reads an object from stream, where its class must be the same as the supplied object, where the loaded object will be stored in.

Exceptions
std::exceptionOn I/O error or different class found.
mrpt::utils::CExceptionEOFOn an End-Of-File condition found at a correct place: an EOF that abruptly finishes in the middle of one object raises a plain std::exception instead.

◆ ReadString()

std::string mrpt::hwdrivers::CSerialPort::ReadString ( const int  total_timeout_ms = -1,
bool *  out_timeout = NULL 
)

Reads one text line from the serial port in POSIX "canonical mode".

This method reads from the serial port until one of the characters in eol are found.

Parameters
eol_charsA line reception is finished when one of these characters is found. Default: LF (10), CR (13).
total_timeout_msIf >0, the maximum number of milliseconds to wait.
out_timeoutIf provided, will hold true on return if a timeout ocurred, false on a valid read.
Returns
The read string, without the final
Exceptions
std::exceptionOn communication errors

◆ receiveMessage()

bool mrpt::utils::CStream::receiveMessage ( utils::CMessage msg)
inherited

Tries to receive a message from the device.

Exceptions
std::exceptionOn communication errors
Returns
True if successful, false if there is no new data from the device (but communications seem to work fine)
See also
The frame format is described in sendMessage()

◆ Seek() [1/2]

virtual uint64_t mrpt::utils::CStream::Seek ( uint64_t  Offset,
CStream::TSeekOrigin  Origin = sFromBeginning 
)
pure virtualinherited

Introduces a pure virtual method for moving to a specified position in the streamed resource.

he Origin parameter indicates how to interpret the Offset parameter. Origin should be one of the following values:

  • sFromBeginning (Default) Offset is from the beginning of the resource. Seek moves to the position Offset. Offset must be >= 0.
  • sFromCurrent Offset is from the current position in the resource. Seek moves to Position + Offset.
  • sFromEnd Offset is from the end of the resource. Offset must be <= 0 to indicate a number of bytes before the end of the file.
    Returns
    Seek returns the new value of the Position property.

Implemented in mrpt::utils::CClientTCPSocket, mrpt::utils::CFileStream, mrpt::utils::CFileGZInputStream, mrpt::utils::CMemoryStream, mrpt::utils::CFileOutputStream, mrpt::utils::CFileInputStream, and mrpt::utils::CStdOutStream.

◆ Seek() [2/2]

uint64_t mrpt::hwdrivers::CSerialPort::Seek ( uint64_t  Offset,
CStream::TSeekOrigin  Origin = sFromBeginning 
)
inline

Introduces a pure virtual method for moving to a specified position in the streamed resource.

he Origin parameter indicates how to interpret the Offset parameter. Origin should be one of the following values:

  • sFromBeginning (Default) Offset is from the beginning of the resource. Seek moves to the position Offset. Offset must be >= 0.
  • sFromCurrent Offset is from the current position in the resource. Seek moves to Position + Offset.
  • sFromEnd Offset is from the end of the resource. Offset must be <= 0 to indicate a number of bytes before the end of the file.
    Returns
    Seek returns the new value of the Position property.

Definition at line 162 of file CSerialPort.h.

References MRPT_END, MRPT_START, MRPT_UNUSED_PARAM, and THROW_EXCEPTION.

◆ sendMessage()

void mrpt::utils::CStream::sendMessage ( const utils::CMessage msg)
inherited

Send a message to the device.

Note that only the low byte from the "type" field will be used.

For frames of size < 255 the frame format is an array of bytes in this order:

<START_FLAG> <HEADER> <LENGTH> <BODY> <END_FLAG>
<START_FLAG> = 0x69
<HEADER> = A header byte
<LENGHT> = Number of bytes of BODY
<BODY> = N x bytes
<END_FLAG> = 0X96
Total length = <LENGTH> + 4

For frames of size > 255 the frame format is an array of bytes in this order:

<START_FLAG> <HEADER> <HIBYTE(LENGTH)> <LOBYTE(LENGTH)> <BODY> <END_FLAG>
<START_FLAG> = 0x79
<HEADER> = A header byte
<LENGHT> = Number of bytes of BODY
<BODY> = N x bytes
<END_FLAG> = 0X96
Total length = <LENGTH> + 5
Exceptions
std::exceptionOn communication errors

◆ setConfig()

void mrpt::hwdrivers::CSerialPort::setConfig ( int  baudRate,
int  parity = 0,
int  bits = 8,
int  nStopBits = 1,
bool  enableFlowControl = false 
)

Changes the configuration of the port.

Parameters
parity0:No parity, 1:Odd, 2:Even (WINDOWS ONLY: 3:Mark, 4:Space)
baudRateThe desired baud rate Accepted values: 50 - 230400
bitsBits per word (typ. 8) Accepted values: 5,6,7,8.
nStopBitsStop bits (typ. 1) Accepted values: 1,2
enableFlowControlWhether to enable the hardware flow control (RTS/CTS) (default=no)
Exceptions
std::exceptionOn communication errors

◆ setSerialPortName()

void mrpt::hwdrivers::CSerialPort::setSerialPortName ( const std::string &  COM_name)
inline

Sets the serial port to open (it is an error to try to change this while open yet).

See also
open, close

Definition at line 69 of file CSerialPort.h.

References THROW_EXCEPTION.

◆ setTimeouts()

void mrpt::hwdrivers::CSerialPort::setTimeouts ( int  ReadIntervalTimeout,
int  ReadTotalTimeoutMultiplier,
int  ReadTotalTimeoutConstant,
int  WriteTotalTimeoutMultiplier,
int  WriteTotalTimeoutConstant 
)

Changes the timeouts of the port, in milliseconds.

Exceptions
std::exceptionOn communication errors

◆ Write()

size_t mrpt::hwdrivers::CSerialPort::Write ( const void *  Buffer,
size_t  Count 
)
virtual

Implements the virtual method responsible for writing to the stream.

Write attempts to write up to Count bytes to Buffer, and returns the number of bytes actually written.

Exceptions
std::exceptionOn communication errors

Implements mrpt::utils::CStream.

◆ WriteBuffer()

void mrpt::utils::CStream::WriteBuffer ( const void *  Buffer,
size_t  Count 
)
inherited

Writes a block of bytes to the stream from Buffer.

Exceptions
std::exceptionOn any error
See also
Important, see: WriteBufferFixEndianness
Note
This method is endianness-dependent.

◆ WriteBufferFixEndianness()

template<typename T >
void mrpt::utils::CStream::WriteBufferFixEndianness ( const T *  ptr,
size_t  ElementCount 
)
inlineinherited

Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running architecture to MRPT stream standard (little endianness).

Parameters
ElementCountThe number of elements (not bytes) to write.
ptrA pointer to the first input element in an array (or std::vector<>, etc...). Example of usage:
vector<float> vec = ...
uint32_t N = vec.size();
s << N
if (N)
s.WriteBufferFixEndianness<float>(&vec[0],N);
Exceptions
std::exceptionOn any error
See also
WriteBuffer

Definition at line 134 of file CStream.h.

◆ WriteObject()

void mrpt::utils::CStream::WriteObject ( const CSerializable o)
inherited

Writes an object to the stream.

Friends And Related Function Documentation

◆ PosixSignalDispatcherImpl

friend class PosixSignalDispatcherImpl
friend

Definition at line 49 of file CSerialPort.h.

Member Data Documentation

◆ hCOM

int mrpt::hwdrivers::CSerialPort::hCOM
protected

The file handle (-1: Not open)

Definition at line 206 of file CSerialPort.h.

◆ m_baudRate

int mrpt::hwdrivers::CSerialPort::m_baudRate
protected

Definition at line 194 of file CSerialPort.h.

◆ m_interBytesTimeout_ms

int mrpt::hwdrivers::CSerialPort::m_interBytesTimeout_ms
protected

Definition at line 195 of file CSerialPort.h.

◆ m_serialName

std::string mrpt::hwdrivers::CSerialPort::m_serialName
protected

The complete name of the serial port device (i.e.

"\\.\COM10","/dev/ttyS2",...)

Definition at line 193 of file CSerialPort.h.

◆ m_timer

CTicTac mrpt::hwdrivers::CSerialPort::m_timer
protected

Used only in ReadString.

Definition at line 197 of file CSerialPort.h.

◆ m_totalTimeout_ms

int mrpt::hwdrivers::CSerialPort::m_totalTimeout_ms
protected

Definition at line 195 of file CSerialPort.h.




Page generated by Doxygen 1.8.14 for MRPT 1.1.0 SVN: at lun oct 28 00:54:49 CET 2019 Hosted on:
SourceForge.net Logo