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

Detailed Description

A definition of a CStream actually representing a USB connection to a FTDI chip.

This class implements the communication with FT245BM / FT245RL chips. Using this class makes a program to depend on:

If there is any error during the communications (or loading the Windows DLL), a std::exception will be raised.

To write bulk data, use CStream::ReadBuffer and CStream::WriteBuffer. See also the derived classes for higher level communication: CInterfaceFTDIMessages

Warning: Avoid defining an object of this class in a global scope if you want to catch all potential exceptions during the constructors (like DLL not found, etc...)

VERSIONS:

See also
CInterfaceFTDIMessages, CStream

Definition at line 73 of file CInterfaceFTDI.h.

#include <mrpt/hwdrivers/CInterfaceFTDI.h>

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

Public Types

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

Public Member Functions

 CInterfaceFTDI ()
 Constructor, which loads driver interface (the DLL under Windows). More...
 
virtual ~CInterfaceFTDI ()
 Destructor, which closes the connection with the chip and unloads the driver interface. More...
 
 CInterfaceFTDI (const CInterfaceFTDI &o)
 This object cannot be copied. More...
 
CInterfaceFTDIoperator= (const CInterfaceFTDI &o)
 This object cannot be copied. More...
 
bool isOpen ()
 Checks whether the chip has been successfully open. More...
 
void OpenBySerialNumber (const std::string &serialNumber)
 Open by device serial number. More...
 
void OpenByDescription (const std::string &description)
 Open by device description. More...
 
void Close ()
 Close the USB device. More...
 
void ResetDevice ()
 Reset the USB device. More...
 
void Purge ()
 Purge the I/O buffers. More...
 
void SetLatencyTimer (unsigned char latency_ms)
 Change the latency timer (in milliseconds) implemented on the FTDI chip: for a few ms, data is not sent to the PC waiting for possible more data, to save USB trafic. More...
 
void SetTimeouts (unsigned long dwReadTimeout_ms, unsigned long dwWriteTimeout_ms)
 Change read & write timeouts, in milliseconds. More...
 
void ListAllDevices (TFTDIDeviceList &outList)
 Generates a list with all FTDI devices connected right now. More...
 
size_t ReadSync (void *Buffer, size_t Count)
 Tries to read, raising no exception if not all the bytes are available, but raising one if there is some communication error. More...
 
size_t WriteSync (const void *Buffer, size_t Count)
 Tries to write, raising no exception if not all the bytes are available, but raising one if there is some communication error. 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...
 
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...
 
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 Member Functions

size_t Read (void *Buffer, size_t Count)
 Introduces a pure virtual method responsible for reading from the stream. More...
 
size_t Write (const void *Buffer, size_t Count)
 Introduces a pure virtual method responsible for writing to the stream. More...
 
uint64_t Seek (uint64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning)
 This virtual method does nothing in this class. More...
 
uint64_t getTotalBytesCount ()
 This virtual method does nothing in this class. More...
 
uint64_t getPosition ()
 This virtual method does nothing in this class. More...
 
void ftdi_read (void *lpvBuffer, unsigned long dwBuffSize, unsigned long *lpdwBytesRead)
 
void ftdi_write (const void *lpvBuffer, unsigned long dwBuffSize, unsigned long *lpdwBytes)
 
void recursive_fill_list_devices (void *usb_device_structure, TFTDIDeviceList &outList)
 Process recursively a USB device and its children: More...
 

Protected Attributes

mrpt::utils::circular_buffer< uint8_t > m_readBuffer
 Used in Read. More...
 
void * m_ftdi_context
 

Member Enumeration Documentation

◆ TSeekOrigin

Used in CStream::Seek.

Enumerator
sFromBeginning 
sFromCurrent 
sFromEnd 

Definition at line 41 of file CStream.h.

Constructor & Destructor Documentation

◆ CInterfaceFTDI() [1/2]

mrpt::hwdrivers::CInterfaceFTDI::CInterfaceFTDI ( )

Constructor, which loads driver interface (the DLL under Windows).

◆ ~CInterfaceFTDI()

virtual mrpt::hwdrivers::CInterfaceFTDI::~CInterfaceFTDI ( )
virtual

Destructor, which closes the connection with the chip and unloads the driver interface.

◆ CInterfaceFTDI() [2/2]

mrpt::hwdrivers::CInterfaceFTDI::CInterfaceFTDI ( const CInterfaceFTDI o)

This object cannot be copied.

Member Function Documentation

◆ Close()

void mrpt::hwdrivers::CInterfaceFTDI::Close ( )

Close the USB device.

◆ CopyFrom()

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

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

◆ ftdi_read()

void mrpt::hwdrivers::CInterfaceFTDI::ftdi_read ( void *  lpvBuffer,
unsigned long  dwBuffSize,
unsigned long *  lpdwBytesRead 
)
protected

◆ ftdi_write()

void mrpt::hwdrivers::CInterfaceFTDI::ftdi_write ( const void *  lpvBuffer,
unsigned long  dwBuffSize,
unsigned long *  lpdwBytes 
)
protected

◆ 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::CInterfaceFTDI::getPosition ( )
protectedvirtual

This virtual method does nothing in this class.

Implements mrpt::utils::CStream.

◆ getTotalBytesCount()

uint64_t mrpt::hwdrivers::CInterfaceFTDI::getTotalBytesCount ( )
protectedvirtual

This virtual method does nothing in this class.

Implements mrpt::utils::CStream.

◆ isOpen()

bool mrpt::hwdrivers::CInterfaceFTDI::isOpen ( )

Checks whether the chip has been successfully open.

See also
OpenBySerialNumber, OpenByDescription

◆ ListAllDevices()

void mrpt::hwdrivers::CInterfaceFTDI::ListAllDevices ( TFTDIDeviceList outList)

Generates a list with all FTDI devices connected right now.

◆ OpenByDescription()

void mrpt::hwdrivers::CInterfaceFTDI::OpenByDescription ( const std::string &  description)

Open by device description.

◆ OpenBySerialNumber()

void mrpt::hwdrivers::CInterfaceFTDI::OpenBySerialNumber ( const std::string &  serialNumber)

Open by device serial number.

◆ 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=()

CInterfaceFTDI& mrpt::hwdrivers::CInterfaceFTDI::operator= ( const CInterfaceFTDI o)

This object cannot be copied.

◆ 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.

◆ Purge()

void mrpt::hwdrivers::CInterfaceFTDI::Purge ( )

Purge the I/O buffers.

◆ Read()

size_t mrpt::hwdrivers::CInterfaceFTDI::Read ( void *  Buffer,
size_t  Count 
)
protectedvirtual

Introduces a pure virtual method responsible for reading from the stream.

It integrates a cache buffer to speed-up sequences of many, small readings.

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::hwdrivers::CInterfaceFTDI::ReadBufferImmediate ( void *  Buffer,
size_t  Count 
)
virtual

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).

In this class this method actually behaves as expected and does not fallback to ReadBuffer().

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

Reimplemented from mrpt::utils::CStream.

◆ 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.

◆ ReadSync()

size_t mrpt::hwdrivers::CInterfaceFTDI::ReadSync ( void *  Buffer,
size_t  Count 
)
inline

Tries to read, raising no exception if not all the bytes are available, but raising one if there is some communication error.

Definition at line 125 of file CInterfaceFTDI.h.

◆ 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()

◆ recursive_fill_list_devices()

void mrpt::hwdrivers::CInterfaceFTDI::recursive_fill_list_devices ( void *  usb_device_structure,
TFTDIDeviceList outList 
)
protected

Process recursively a USB device and its children:

◆ ResetDevice()

void mrpt::hwdrivers::CInterfaceFTDI::ResetDevice ( )

Reset the USB device.

◆ 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::CInterfaceFTDI::Seek ( uint64_t  Offset,
CStream::TSeekOrigin  Origin = sFromBeginning 
)
protected

This virtual method does nothing in this class.

◆ 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

◆ SetLatencyTimer()

void mrpt::hwdrivers::CInterfaceFTDI::SetLatencyTimer ( unsigned char  latency_ms)

Change the latency timer (in milliseconds) implemented on the FTDI chip: for a few ms, data is not sent to the PC waiting for possible more data, to save USB trafic.

◆ SetTimeouts()

void mrpt::hwdrivers::CInterfaceFTDI::SetTimeouts ( unsigned long  dwReadTimeout_ms,
unsigned long  dwWriteTimeout_ms 
)

Change read & write timeouts, in milliseconds.

◆ Write()

size_t mrpt::hwdrivers::CInterfaceFTDI::Write ( const void *  Buffer,
size_t  Count 
)
protectedvirtual

Introduces a pure 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.

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.

◆ WriteSync()

size_t mrpt::hwdrivers::CInterfaceFTDI::WriteSync ( const void *  Buffer,
size_t  Count 
)
inline

Tries to write, raising no exception if not all the bytes are available, but raising one if there is some communication error.

Definition at line 132 of file CInterfaceFTDI.h.

Member Data Documentation

◆ m_ftdi_context

void* mrpt::hwdrivers::CInterfaceFTDI::m_ftdi_context
protected

Definition at line 226 of file CInterfaceFTDI.h.

◆ m_readBuffer

mrpt::utils::circular_buffer<uint8_t> mrpt::hwdrivers::CInterfaceFTDI::m_readBuffer
protected

Used in Read.

Definition at line 149 of file CInterfaceFTDI.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