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:
Definition at line 47 of file CSerialPort.h.
#include <mrpt/comms/CSerialPort.h>
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 () const |
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=nullptr, 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... | |
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 | |
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 | |
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 |
mrpt::utils::CTicTac | m_timer |
Used only in ReadString. More... | |
int | hCOM |
The file handle (-1: Not open) More... | |
Friends | |
class | PosixSignalDispatcherImpl |
|
inherited |
CSerialPort::CSerialPort | ( | const std::string & | portName, |
bool | openNow = true |
||
) |
Constructor.
portName | The serial port to open. See comments at the begining of this page. |
openNow | Whether to try to open the port now. If not selected, the port should be open later with "open()". |
Definition at line 53 of file CSerialPort.cpp.
References open().
CSerialPort::CSerialPort | ( | ) |
Default constructor: it does not open any port - later you must call "setSerialPortName" and then "open".
Definition at line 67 of file CSerialPort.cpp.
|
virtual |
Destructor.
Definition at line 80 of file CSerialPort.cpp.
References close(), and isOpen().
void CSerialPort::close | ( | ) |
Close the port.
If is already closed, results in no action.
Definition at line 620 of file CSerialPort.cpp.
References hCOM, MRPT_END, and MRPT_START.
Referenced by mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CNTRIPEmitter::initialize(), Read(), ReadString(), mrpt::hwdrivers::CGillAnemometer::~CGillAnemometer(), mrpt::hwdrivers::CGyroKVHDSP3000::~CGyroKVHDSP3000(), mrpt::hwdrivers::CNTRIPEmitter::~CNTRIPEmitter(), mrpt::hwdrivers::CRaePID::~CRaePID(), and ~CSerialPort().
|
inherited |
Reads from the stream until a '
' character is found ('' characters are ignored).
Definition at line 780 of file CStream.cpp.
|
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 202 of file CSerialPort.h.
References MRPT_END, MRPT_START, and THROW_EXCEPTION.
|
inlinevirtual |
Returns the total amount of bytes in the stream.
Implements mrpt::utils::CStream.
Definition at line 191 of file CSerialPort.h.
References MRPT_END, MRPT_START, and THROW_EXCEPTION.
|
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 CSerialPort::isOpen | ( | ) | const |
Returns if port has been correctly open.
Definition at line 185 of file CSerialPort.cpp.
References hCOM.
Referenced by mrpt::hwdrivers::CHokuyoURG::checkCOMisOpen(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), mrpt::hwdrivers::CGPSInterface::OnConnectionShutdown(), open(), purgeBuffers(), Read(), ReadString(), setConfig(), setSerialPortName(), setTimeouts(), mrpt::hwdrivers::CCANBusReader::tryToOpenComms(), mrpt::hwdrivers::CSickLaserSerial::tryToOpenComms(), Write(), mrpt::hwdrivers::CNTRIPEmitter::~CNTRIPEmitter(), and ~CSerialPort().
void CSerialPort::open | ( | ) |
Open the port.
If is already open results in no action.
std::exception | On communication errors |
Definition at line 88 of file CSerialPort.cpp.
References hCOM, m_serialName, MRPT_END, MRPT_START, THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
Referenced by mrpt::hwdrivers::CHokuyoURG::checkCOMisOpen(), CSerialPort(), mrpt::hwdrivers::CNTRIPEmitter::initialize(), open(), mrpt::hwdrivers::CCANBusReader::tryToOpenComms(), and mrpt::hwdrivers::CSickLaserSerial::tryToOpenComms().
|
inline |
Open the given serial port.
If it is already open and the name does not match, an exception is raised.
std::exception | On communication errors or a different serial port already open. |
Definition at line 90 of file CSerialPort.h.
References isOpen(), m_serialName, open(), setSerialPortName(), and THROW_EXCEPTION.
|
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.
|
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 CSerialPort::purgeBuffers | ( | ) |
Purge tx and rx buffers.
std::exception | On communication errors |
Definition at line 891 of file CSerialPort.cpp.
References hCOM, isOpen(), MRPT_END, MRPT_START, THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
Referenced by mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::CGPSInterface::legacy_topcon_setup_commands(), mrpt::hwdrivers::CSickLaserSerial::LMS_setupSerialComms(), mrpt::hwdrivers::CGPSInterface::OnConnectionEstablished(), mrpt::hwdrivers::CHokuyoURG::purgeBuffers(), mrpt::hwdrivers::CCANBusReader::setupSerialComms(), mrpt::hwdrivers::CHokuyoURG::turnOn(), and mrpt::hwdrivers::CGPSInterface::unsetJAVAD_AIM_mode().
|
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.
std::exception | On communication errors |
Implements mrpt::utils::CStream.
Definition at line 643 of file CSerialPort.cpp.
References close(), hCOM, isOpen(), m_interBytesTimeout_ms, m_timer, m_totalTimeout_ms, min, MRPT_END, MRPT_START, mrpt::utils::CTicTac::Tac(), THROW_EXCEPTION, and mrpt::utils::CTicTac::Tic().
Referenced by mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CGPSInterface::JAVAD_sendMessage(), mrpt::hwdrivers::CSickLaserSerial::LMS_waitACK(), mrpt::hwdrivers::CSickLaserSerial::LMS_waitIncomingFrame(), mrpt::hwdrivers::CCANBusReader::waitACK(), mrpt::hwdrivers::CCANBusReader::waitContinuousSampleFrame(), mrpt::hwdrivers::CSickLaserSerial::waitContinuousSampleFrame(), mrpt::hwdrivers::CCANBusReader::waitForVersion(), and mrpt::hwdrivers::CCANBusReader::waitIncomingFrame().
|
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().
|
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.
std::exception | On any error, or if ZERO bytes are read. |
Reimplemented in mrpt::comms::CInterfaceFTDI.
Definition at line 129 of file CStream.h.
References mrpt::utils::CStream::ReadBuffer().
|
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().
std::string CSerialPort::ReadString | ( | const int | total_timeout_ms = -1 , |
bool * | out_timeout = nullptr , |
||
const char * | eol_chars = "\r\n" |
||
) |
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.
eol_chars | A line reception is finished when one of these characters is found. Default: LF (10), CR (13). |
total_timeout_ms | If >0, the maximum number of milliseconds to wait. |
out_timeout | If provided, will hold true on return if a timeout ocurred, false on a valid read. |
std::exception | On communication errors |
This method reads from the serial port until one of the characters in eol are found.
Definition at line 731 of file CSerialPort.cpp.
References ASSERT_, close(), hCOM, isOpen(), m_timer, MRPT_TRY_END, MRPT_TRY_START, mrpt::utils::CTicTac::Tac(), THROW_EXCEPTION, and mrpt::utils::CTicTac::Tic().
Referenced by mrpt::hwdrivers::CGyroKVHDSP3000::doProcess().
|
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().
|
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:
Definition at line 179 of file CSerialPort.h.
References MRPT_END, MRPT_START, MRPT_UNUSED_PARAM, and THROW_EXCEPTION.
|
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 CSerialPort::setConfig | ( | int | baudRate, |
int | parity = 0 , |
||
int | bits = 8 , |
||
int | nStopBits = 1 , |
||
bool | enableFlowControl = false |
||
) |
Changes the configuration of the port.
parity | 0:No parity, 1:Odd, 2:Even (WINDOWS ONLY: 3:Mark, 4:Space) |
baudRate | The desired baud rate Accepted values: 50 - 230400 |
bits | Bits per word (typ. 8) Accepted values: 5,6,7,8. |
nStopBits | Stop bits (typ. 1) Accepted values: 1,2 |
enableFlowControl | Whether to enable the hardware flow control (RTS/CTS) (default=no) |
std::exception | On communication errors |
Definition at line 197 of file CSerialPort.cpp.
References ASSERT_, hCOM, isOpen(), m_baudRate, MRPT_END, MRPT_START, THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
Referenced by mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), mrpt::hwdrivers::CSickLaserSerial::LMS_setupSerialComms(), mrpt::hwdrivers::CCANBusReader::setupSerialComms(), mrpt::hwdrivers::CCANBusReader::tryToOpenComms(), mrpt::hwdrivers::CSickLaserSerial::tryToOpenComms(), and mrpt::hwdrivers::CHokuyoURG::turnOn().
|
inline |
Sets the serial port to open (it is an error to try to change this while open yet).
Definition at line 74 of file CSerialPort.h.
References isOpen(), m_serialName, and THROW_EXCEPTION.
Referenced by open(), mrpt::hwdrivers::CCANBusReader::tryToOpenComms(), and mrpt::hwdrivers::CSickLaserSerial::tryToOpenComms().
void CSerialPort::setTimeouts | ( | int | ReadIntervalTimeout, |
int | ReadTotalTimeoutMultiplier, | ||
int | ReadTotalTimeoutConstant, | ||
int | WriteTotalTimeoutMultiplier, | ||
int | WriteTotalTimeoutConstant | ||
) |
Changes the timeouts of the port, in milliseconds.
std::exception | On communication errors |
Definition at line 559 of file CSerialPort.cpp.
References hCOM, isOpen(), m_interBytesTimeout_ms, m_totalTimeout_ms, MRPT_END, MRPT_START, THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
Referenced by mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::CCANBusReader::tryToOpenComms(), mrpt::hwdrivers::CSickLaserSerial::tryToOpenComms(), and mrpt::hwdrivers::CHokuyoURG::turnOn().
|
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.
std::exception | On communication errors |
Implements mrpt::utils::CStream.
Definition at line 826 of file CSerialPort.cpp.
References hCOM, isOpen(), MRPT_END, MRPT_START, THROW_EXCEPTION, and THROW_EXCEPTION_FMT.
Referenced by mrpt::hwdrivers::CGyroKVHDSP3000::changeMode(), mrpt::hwdrivers::CGPSInterface::JAVAD_sendMessage(), mrpt::hwdrivers::CGyroKVHDSP3000::resetIncrementalAngle(), mrpt::hwdrivers::CCANBusReader::sendCommandToCANReader(), and mrpt::hwdrivers::CSickLaserSerial::SendCommandToSICK().
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::CWirelessPowerGridMap2D::writeToStream(), mrpt::maps::CGasConcentrationGridMap2D::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().
|
inlineinherited |
Writes a Variant to the stream.
Definition at line 312 of file CStream.h.
References mrpt::utils::CStream::WriteObject().
|
friend |
Definition at line 49 of file CSerialPort.h.
|
protected |
The file handle (-1: Not open)
Definition at line 228 of file CSerialPort.h.
Referenced by close(), isOpen(), open(), purgeBuffers(), Read(), ReadString(), setConfig(), setTimeouts(), and Write().
|
protected |
Definition at line 215 of file CSerialPort.h.
Referenced by setConfig().
|
protected |
Definition at line 216 of file CSerialPort.h.
Referenced by Read(), and setTimeouts().
|
protected |
The complete name of the serial port device (i.e.
"\\.\COM10","/dev/ttyS2",...)
Definition at line 214 of file CSerialPort.h.
Referenced by open(), and setSerialPortName().
|
protected |
Used only in ReadString.
Definition at line 219 of file CSerialPort.h.
Referenced by Read(), and ReadString().
|
protected |
Definition at line 216 of file CSerialPort.h.
Referenced by Read(), and setTimeouts().
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 |