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.
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:
Definition at line 75 of file CInterfaceFTDI.h.
#include <mrpt/comms/CInterfaceFTDI.h>
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... | |
CInterfaceFTDI & | operator= (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... | |
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... | |
void | WriteObject (const CSerializable &o) |
CSerializable::Ptr | ReadObject () |
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object. More... | |
template<typename T > | |
T::Ptr | 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... | |
template<typename... T> | |
mrpt::utils::variant< T... > | ReadVariant () |
Reads a variant from stream, its class determined at runtime, and returns a variant to the object. More... | |
template<typename T > | |
void | WriteVariant (T t) |
Writes a Variant to the stream. More... | |
template<typename T > | |
T | ReadPOD () |
Reads a simple POD type and returns by value. More... | |
CStream & | operator<< (const CSerializable::Ptr &pObj) |
Write an object to a stream in the binary MRPT format. More... | |
CStream & | operator<< (const CSerializable &obj) |
Write an object to a stream in the binary MRPT format. More... | |
CStream & | operator>> (CSerializable::Ptr &pObj) |
CStream & | operator>> (CSerializable &obj) |
template<typename STORED_TYPE , typename CAST_TO_TYPE > | |
void | ReadAsAndCastTo (CAST_TO_TYPE &read_here) |
Read a value from a stream stored in a type different of the target variable, making the conversion via static_cast. More... | |
virtual int | printf (const char *fmt,...) MRPT_printf_format_check(2 |
Writes a string to the stream in a textual form. More... | |
template<typename CONTAINER_TYPE > | |
virtual int void | printf_vector (const char *fmt, const CONTAINER_TYPE &V, char separator=',') |
Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element T . 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... | |
void | internal_ReadObject (CSerializable *newObj, const std::string &className, bool isOldFormat, int8_t version) |
Read the object. More... | |
void | internal_ReadObjectHeader (std::string &className, bool &isOldFormat, int8_t &version) |
Read the object Header. More... | |
Protected Attributes | |
mrpt::utils::circular_buffer< uint8_t > | m_readBuffer |
Used in Read. More... | |
void * | m_ftdi_context |
|
inherited |
mrpt::comms::CInterfaceFTDI::CInterfaceFTDI | ( | ) |
Constructor, which loads driver interface (the DLL under Windows).
|
virtual |
Destructor, which closes the connection with the chip and unloads the driver interface.
mrpt::comms::CInterfaceFTDI::CInterfaceFTDI | ( | const CInterfaceFTDI & | o | ) |
This object cannot be copied.
void mrpt::comms::CInterfaceFTDI::Close | ( | ) |
Close the USB device.
Referenced by mrpt::hwdrivers::CServoeNeck::checkConnectionAndConnect(), mrpt::hwdrivers::CServoeNeck::disableServo(), mrpt::hwdrivers::CServoeNeck::enableServo(), mrpt::hwdrivers::CServoeNeck::getRegisterValue(), mrpt::hwdrivers::CServoeNeck::queryFirmwareVersion(), mrpt::hwdrivers::CServoeNeck::setRegisterValue(), mrpt::hwdrivers::CServoeNeck::setRegisterValueAndSpeed(), and mrpt::hwdrivers::CSickLaserUSB::waitContinuousSampleFrame().
|
inherited |
Reads from the stream until a '
' character is found ('' characters are ignored).
Definition at line 780 of file CStream.cpp.
|
protectedvirtual |
This virtual method does nothing in this class.
Implements mrpt::utils::CStream.
Definition at line 84 of file CInterfaceFTDI_common.cpp.
|
protectedvirtual |
This virtual method does nothing in this class.
Implements mrpt::utils::CStream.
Definition at line 80 of file CInterfaceFTDI_common.cpp.
|
protectedinherited |
Read the object.
Definition at line 523 of file CStream.cpp.
References SERIALIZATION_END_FLAG, THROW_EXCEPTION, THROW_EXCEPTION_FMT, and THROW_TYPED_EXCEPTION.
Referenced by mrpt::utils::CStream::ReadObject(), and mrpt::utils::CStream::ReadVariant().
|
protectedinherited |
Read the object Header.
Definition at line 420 of file CStream.cpp.
References ASSERT_, THROW_EXCEPTION, THROW_STACKED_EXCEPTION_CUSTOM_MSG2, and THROW_TYPED_EXCEPTION.
Referenced by mrpt::utils::CStream::ReadObject(), and mrpt::utils::CStream::ReadVariant().
bool mrpt::comms::CInterfaceFTDI::isOpen | ( | ) |
Checks whether the chip has been successfully open.
Referenced by mrpt::hwdrivers::CServoeNeck::checkConnectionAndConnect(), mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected(), mrpt::hwdrivers::CServoeNeck::disableServo(), mrpt::hwdrivers::CServoeNeck::enableServo(), mrpt::hwdrivers::CServoeNeck::getRegisterValue(), mrpt::hwdrivers::CServoeNeck::setRegisterValue(), and mrpt::hwdrivers::CServoeNeck::setRegisterValueAndSpeed().
void mrpt::comms::CInterfaceFTDI::ListAllDevices | ( | TFTDIDeviceList & | outList | ) |
Generates a list with all FTDI devices connected right now.
void mrpt::comms::CInterfaceFTDI::OpenByDescription | ( | const std::string & | description | ) |
Open by device description.
void mrpt::comms::CInterfaceFTDI::OpenBySerialNumber | ( | const std::string & | serialNumber | ) |
Open by device serial number.
Referenced by mrpt::hwdrivers::CServoeNeck::checkConnectionAndConnect(), and mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
inherited |
Write an object to a stream in the binary MRPT format.
Definition at line 201 of file CStream.cpp.
|
inherited |
Write an object to a stream in the binary MRPT format.
Definition at line 208 of file CStream.cpp.
CInterfaceFTDI& mrpt::comms::CInterfaceFTDI::operator= | ( | const CInterfaceFTDI & | o | ) |
This object cannot be copied.
|
inherited |
Definition at line 214 of file CStream.cpp.
|
inherited |
Definition at line 220 of file CStream.cpp.
|
virtualinherited |
Writes a string to the stream in a textual form.
Definition at line 597 of file CStream.cpp.
References MRPT_END, MRPT_START, and vsnprintf.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::utils::TMatchingPairList::dumpToFile(), mrpt::obs::gnss::Message_NMEA_GGA::dumpToStream(), mrpt::obs::gnss::Message_TOPCON_PZS::dumpToStream(), mrpt::obs::gnss::Message_TOPCON_SATS::dumpToStream(), mrpt::obs::gnss::Message_NMEA_GLL::dumpToStream(), mrpt::obs::gnss::Message_NMEA_RMC::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::dumpToStream(), mrpt::obs::CObservationGPS::dumpToStream(), mrpt::obs::gnss::Message_NMEA_VTG::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NMEA_ZDA::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::dumpToStream(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::maps::TMetricMapInitializer::dumpToTextStream(), mrpt::slam::CIncrementalMapPartitioner::TOptions::dumpToTextStream(), mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_FabMap::TOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions::dumpToTextStream(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::dumpToTextStream(), mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::slam::CICP::TConfigParams::dumpToTextStream(), mrpt::slam::CGridMapAligner::TConfigParams::dumpToTextStream(), mrpt::graphslam::TSlidingWindow::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::bayes::TKF_options::dumpToTextStream(), mrpt::utils::CLoadableOptions::dumpToTextStream(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::dumpToTextStream(), mrpt::vision::CFeatureExtraction::TOptions::dumpToTextStream(), mrpt::maps::CHeightGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::TInsertionOptions::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TLikelihoodOptions::dumpToTextStream(), mrpt::maps::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TInsertionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM::TOptions::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::CPointsMap::TInsertionOptions::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::dumpToTextStream(), mrpt::maps::CLandmarksMap::TInsertionOptions::dumpToTextStream(), mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::TLikelihoodOptions::dumpToTextStream(), mrpt::vision::TStereoSystemParams::dumpToTextStream(), mrpt::maps::CColouredPointsMap::TColourOptions::dumpToTextStream(), mrpt::maps::CPointsMap::TLikelihoodOptions::dumpToTextStream(), mrpt::vision::CFeature::dumpToTextStream(), mrpt::maps::TSetOfMetricMapInitializers::dumpToTextStream(), mrpt::maps::CLandmarksMap::TLikelihoodOptions::dumpToTextStream(), mrpt::hmtslam::CHMTSLAM::TOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams::dumpToTextStream(), mrpt::vision::TMatchingOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::vision::TMultiResDescOptions::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CHeightGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CLandmarksMap::TMapDefinition::dumpToTextStream_map_specific(), mrpt::utils::CLoadableOptions::dumpVar_bool(), mrpt::utils::CLoadableOptions::dumpVar_double(), mrpt::utils::CLoadableOptions::dumpVar_float(), mrpt::utils::CLoadableOptions::dumpVar_int(), mrpt::utils::CLoadableOptions::dumpVar_string(), generic_dump_BESTPOS(), generic_dump_MARKTIME(), mrpt::maps::CRandomFieldGridMap2D::TInsertionOptionsCommon::internal_dumpToTextStream_common(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetObservationsAndDataAssociation(), mrpt::utils::CStream::printf_vector(), mrpt::maps::CRandomFieldGridMap3D::saveAsCSV(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), mrpt::utils::CTimeLogger::saveToCSVFile(), and mrpt::poses::CPoseInterpolatorBase< 3 >::saveToTextFile().
|
inlineinherited |
Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element T
.
CONTAINER_TYPE | can be any vector<T>, deque<T> or alike. |
Definition at line 370 of file CStream.h.
References mrpt::utils::CStream::printf().
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel().
void mrpt::comms::CInterfaceFTDI::Purge | ( | ) |
Purge the I/O buffers.
Referenced by mrpt::hwdrivers::CServoeNeck::checkConnectionAndConnect().
|
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.
Definition at line 21 of file CInterfaceFTDI_common.cpp.
References mrpt::utils::circular_buffer< T >::available(), ftdi_read(), m_readBuffer, min, mrpt::utils::circular_buffer< T >::pop_many(), mrpt::utils::circular_buffer< T >::push_many(), and mrpt::utils::circular_buffer< T >::size().
Referenced by ReadSync().
|
inlineinherited |
|
inherited |
Reads a block of bytes from the stream into Buffer.
std::exception | On any error, or if ZERO bytes are read. |
Definition at line 40 of file CStream.cpp.
References ASSERT_, and THROW_EXCEPTION.
Referenced by mrpt::hwdrivers::CHokuyoURG::assureBufferHasBytes(), mrpt::compress::zip::compress_gz_data_block(), mrpt::compress::zip::decompress(), mrpt::compress::zip::decompress_gz_file(), mrpt::hwdrivers::CGPSInterface::doProcess(), fill_input_buffer(), mrpt::system::loadBinaryFile(), mrpt::utils::CMemoryStream::loadBufferFromFile(), mrpt::hwdrivers::CHokuyoURG::purgeBuffers(), mrpt::utils::CStream::ReadBufferFixEndianness(), and mrpt::utils::CStream::ReadBufferImmediate().
|
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.
ElementCount | The number of elements (not bytes) to read. |
ptr | A pointer to the first output element in an array (or std::vector<>, etc...). |
std::exception | On any error, or if ZERO bytes are read. |
Definition at line 108 of file CStream.h.
References mrpt::utils::CStream::ReadBuffer(), and mrpt::mrpt::utils::reverseBytesInPlace().
Referenced by mrpt::math::operator>>(), mrpt::utils::CStream::ReadPOD(), and triangle_readFromStream().
|
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().
std::exception | On any error, or if ZERO bytes are read. |
Reimplemented from mrpt::utils::CStream.
Definition at line 88 of file CInterfaceFTDI_common.cpp.
References ftdi_read().
|
inlineinherited |
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object.
std::exception | On I/O error or undefined class. |
mrpt::utils::CExceptionEOF | On 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. |
Definition at line 207 of file CStream.h.
Referenced by mrpt::utils::mrpt_recv_from_zmq(), mrpt::utils::mrpt_recv_from_zmq_into(), mrpt::utils::OctetVectorToObject(), mrpt::utils::operator>>(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::utils::RawStringToObject(), mrpt::utils::StringToObject(), and TEST().
|
inlineinherited |
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object.
This version is similar to mrpt::make_aligned_shared<T>.
std::exception | On I/O error or undefined class. |
mrpt::utils::CExceptionEOF | On 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. |
Definition at line 217 of file CStream.h.
References mrpt::utils::TRuntimeClassId::createObject(), mrpt::utils::findRegisteredClass(), mrpt::utils::CStream::internal_ReadObject(), and mrpt::utils::CStream::internal_ReadObjectHeader().
|
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.
std::exception | On I/O error or different class found. |
mrpt::utils::CExceptionEOF | On 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. |
Definition at line 566 of file CStream.cpp.
References ASSERT_, mrpt::utils::TRuntimeClassId::className, mrpt::utils::findRegisteredClass(), mrpt::format(), mrpt::utils::CSerializable::GetRuntimeClass(), THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
|
inlineinherited |
Reads a simple POD type and returns by value.
Useful when stream >> var;
cannot be used becuase of errors of misaligned reference binding. Use with macro MRPT_READ_POD
to avoid typing the type T yourself.
s << var;
is safe for misaligned variables. Definition at line 325 of file CStream.h.
References mrpt::utils::CStream::ReadBufferFixEndianness().
|
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 131 of file CInterfaceFTDI.h.
References Read().
Referenced by mrpt::hwdrivers::CSickLaserUSB::waitContinuousSampleFrame().
|
inlineinherited |
Reads a variant from stream, its class determined at runtime, and returns a variant to the object.
To be compatible with the current polymorphic system this support smart pointer types. For pointer types, This will bind to the first possible pointer type. variant<CSerializable::Ptr, CRenderizable::Ptr>
std::exception | On I/O error or undefined class. |
mrpt::utils::CExceptionEOF | On 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. |
Definition at line 282 of file CStream.h.
References mrpt::utils::TRuntimeClassId::createObject(), mrpt::utils::findRegisteredClass(), mrpt::utils::CStream::internal_ReadObject(), mrpt::utils::CStream::internal_ReadObjectHeader(), mrpt::utils::CStream::ReadVariant_helper(), and THROW_EXCEPTION_FMT.
Referenced by mrpt::utils::operator>>().
|
inherited |
Tries to receive a message from the device.
std::exception | On communication errors |
Definition at line 686 of file CStream.cpp.
References mrpt::utils::CMessage::content, MAKEWORD16B, mrpt::system::os::memcpy(), MRPT_END, MRPT_START, and mrpt::utils::CMessage::type.
Referenced by mrpt::hwdrivers::CServoeNeck::disableServo(), mrpt::hwdrivers::CServoeNeck::enableServo(), mrpt::hwdrivers::CRoboticHeadInterface::Get3SoundBuffer(), mrpt::hwdrivers::CRoboticHeadInterface::GetGain(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CServoeNeck::getRegisterValue(), mrpt::hwdrivers::CRoboticHeadInterface::GetSoundLocation(), mrpt::hwdrivers::CServoeNeck::queryFirmwareVersion(), mrpt::hwdrivers::CBoardENoses::queryFirmwareVersion(), mrpt::hwdrivers::CRoboticHeadInterface::SetGain(), mrpt::hwdrivers::CServoeNeck::setRegisterValue(), and mrpt::hwdrivers::CServoeNeck::setRegisterValueAndSpeed().
|
protected |
Process recursively a USB device and its children:
void mrpt::comms::CInterfaceFTDI::ResetDevice | ( | ) |
Reset the USB device.
Referenced by mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
protected |
This virtual method does nothing in this class.
Definition at line 70 of file CInterfaceFTDI_common.cpp.
References MRPT_UNUSED_PARAM.
|
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:
Implemented in mrpt::utils::CFileStream, mrpt::utils::CFileGZInputStream, mrpt::utils::CFileOutputStream, mrpt::utils::CMemoryStream, mrpt::utils::CFileInputStream, and mrpt::utils::CStdOutStream.
|
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:
For frames of size > 255 the frame format is an array of bytes in this order:
std::exception | On communication errors |
Definition at line 649 of file CStream.cpp.
References mrpt::utils::CMessage::content, mrpt::system::os::memcpy(), MRPT_END, MRPT_START, and mrpt::utils::CMessage::type.
Referenced by mrpt::hwdrivers::CServoeNeck::disableServo(), mrpt::hwdrivers::CServoeNeck::enableServo(), mrpt::hwdrivers::CRoboticHeadInterface::Get3SoundBuffer(), mrpt::hwdrivers::CRoboticHeadInterface::GetGain(), mrpt::hwdrivers::CServoeNeck::getRegisterValue(), mrpt::hwdrivers::CRoboticHeadInterface::GetSoundLocation(), mrpt::hwdrivers::CServoeNeck::queryFirmwareVersion(), mrpt::hwdrivers::CBoardENoses::queryFirmwareVersion(), mrpt::hwdrivers::CRoboticHeadInterface::SetGain(), mrpt::hwdrivers::CServoeNeck::setRegisterValue(), and mrpt::hwdrivers::CServoeNeck::setRegisterValueAndSpeed().
void mrpt::comms::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.
Referenced by mrpt::hwdrivers::CServoeNeck::checkConnectionAndConnect(), and mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
void mrpt::comms::CInterfaceFTDI::SetTimeouts | ( | unsigned long | dwReadTimeout_ms, |
unsigned long | dwWriteTimeout_ms | ||
) |
Change read & write timeouts, in milliseconds.
Referenced by mrpt::hwdrivers::CServoeNeck::checkConnectionAndConnect(), and mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
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.
Definition at line 60 of file CInterfaceFTDI_common.cpp.
References ftdi_write().
Referenced by WriteSync().
Writes a block of bytes to the stream from Buffer.
std::exception | On any error |
Definition at line 64 of file CStream.cpp.
References ASSERT_, and THROW_EXCEPTION.
Referenced by mrpt::compress::zip::compress(), mrpt::utils::CMessage::deserializeIntoExistingObject(), mrpt::utils::CMessage::deserializeIntoNewObject(), mrpt::hwdrivers::CHokuyoURG::displaySensorInfo(), mrpt::hwdrivers::CHokuyoURG::displayVersionInfo(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), empty_output_buffer(), mrpt::hwdrivers::CHokuyoURG::enableSCIP20(), mrpt::hwdrivers::CGPSInterface::implement_parser_NOVATEL_OEM6(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::internal_writeToStream(), mrpt::utils::mrpt_recv_from_zmq_buf(), mrpt::utils::ObjectToString(), mrpt::hwdrivers::CGPSInterface::OnConnectionEstablished(), mrpt::hwdrivers::CGPSInterface::OnConnectionShutdown(), mrpt::utils::operator<<(), mrpt::utils::CMemoryStream::saveBufferToFile(), mrpt::hwdrivers::CGPSInterface::sendCustomCommand(), mrpt::hwdrivers::CBoardENoses::setActiveChamber(), mrpt::hwdrivers::CHokuyoURG::setHighBaudrate(), mrpt::hwdrivers::CHokuyoURG::setHighSensitivityMode(), mrpt::hwdrivers::CHokuyoURG::setMotorSpeed(), mrpt::hwdrivers::CHokuyoURG::startScanningMode(), mrpt::utils::StringToObject(), mrpt::hwdrivers::CHokuyoURG::switchLaserOff(), mrpt::hwdrivers::CHokuyoURG::switchLaserOn(), term_destination(), mrpt::system::vectorToBinaryFile(), mrpt::utils::CStream::WriteBufferFixEndianness(), mrpt::nav::CLogFileRecord::writeToStream(), mrpt::maps::CGasConcentrationGridMap2D::writeToStream(), mrpt::maps::CWirelessPowerGridMap2D::writeToStream(), mrpt::maps::CHeightGridMap2D_MRF::writeToStream(), mrpt::maps::CReflectivityGridMap2D::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::maps::COccupancyGridMap2D::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), mrpt::maps::CRandomFieldGridMap3D::writeToStream(), mrpt::utils::CImage::writeToStream(), and mrpt::opengl::CRenderizable::writeToStreamRender().
|
inlineinherited |
Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running architecture to MRPT stream standard (little endianness).
ElementCount | The number of elements (not bytes) to write. |
ptr | A pointer to the first input element in an array (or std::vector<>, etc...). Example of usage: |
std::exception | On any error |
Definition at line 159 of file CStream.h.
References mrpt::utils::CStream::WriteBuffer().
Referenced by mrpt::math::operator<<(), triangle_writeToStream(), mrpt::math::CMatrix::writeToStream(), mrpt::math::CMatrixD::writeToStream(), mrpt::maps::CWeightedPointsMap::writeToStream(), mrpt::maps::CColouredPointsMap::writeToStream(), mrpt::maps::CSimplePointsMap::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::maps::COccupancyGridMap2D::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().
|
inherited |
Writes an object to the stream.
Definition at line 158 of file CStream.cpp.
References ASSERT_, mrpt::utils::TRuntimeClassId::className, mrpt::utils::CSerializable::GetRuntimeClass(), MRPT_END, MRPT_START, SERIALIZATION_END_FLAG, and mrpt::utils::CSerializable::writeToStream().
Referenced by mrpt::utils::mrpt_send_to_zmq(), mrpt::utils::ObjectToOctetVector(), mrpt::utils::ObjectToRawString(), mrpt::utils::ObjectToString(), mrpt::math::operator<<(), mrpt::utils::CMessage::serializeObject(), and mrpt::utils::CStream::WriteVariant().
|
inlineinherited |
Definition at line 198 of file CStream.h.
References mrpt::utils::CStream::WriteObject().
Referenced by mrpt::utils::CStream::WriteObject().
|
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 135 of file CInterfaceFTDI.h.
References Write().
|
inlineinherited |
Writes a Variant to the stream.
Definition at line 312 of file CStream.h.
References mrpt::utils::CStream::WriteObject().
|
protected |
Definition at line 243 of file CInterfaceFTDI.h.
|
protected |
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019 |