Main MRPT website > C++ reference for MRPT 1.5.7
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
mrpt::utils::CMemoryStream Class Reference

Detailed Description

This CStream derived class allow using a memory buffer as a CStream.

This class is useful for storing any required set of variables or objects, and then read them to other objects, or storing them to a file, for example.

See also
CStream

Definition at line 26 of file CMemoryStream.h.

#include <mrpt/utils/CMemoryStream.h>

Inheritance diagram for mrpt::utils::CMemoryStream:
Inheritance graph

Public Types

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

Public Member Functions

 CMemoryStream ()
 Default constructor. More...
 
 CMemoryStream (const void *data, const uint64_t nBytesInData)
 Constructor to initilize the data in the stream from a block of memory (which is copied), and sets the current stream position at the beginning of the data. More...
 
void assignMemoryNotOwn (const void *data, const uint64_t nBytesInData)
 Initilize the data in the stream from a block of memory which is NEITHER OWNED NOR COPIED by the object, so it must exist during the whole live of the object. More...
 
virtual ~CMemoryStream ()
 Destructor. More...
 
void Clear ()
 Clears the memory buffer. More...
 
void changeSize (uint64_t newSize)
 Change size. This would be rarely used. Use ">>" operators for writing to stream. More...
 
uint64_t Seek (int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) MRPT_OVERRIDE
 Introduces a pure virtual method for moving to a specified position in the streamed resource. More...
 
uint64_t getTotalBytesCount () MRPT_OVERRIDE
 Returns the total size of the internal buffer. More...
 
uint64_t getPosition () MRPT_OVERRIDE
 Method for getting the current cursor position, where 0 is the first byte and TotalBytesCount-1 the last one. More...
 
voidgetRawBufferData ()
 Method for getting a pointer to the raw stored data. More...
 
bool saveBufferToFile (const std::string &file_name)
 Saves the entire buffer to a file. More...
 
bool loadBufferFromFile (const std::string &file_name)
 Loads the entire buffer from a file *. More...
 
void setAllocBlockSize (uint64_t alloc_block_size)
 Change the size of the additional memory block that is reserved whenever the current block runs too short (default=0x10000 bytes) 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...
 
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)
 
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) MRPT_OVERRIDE
 Introduces a pure virtual method responsible for reading from the stream. More...
 
size_t Write (const void *Buffer, size_t Count) MRPT_OVERRIDE
 Introduces a pure virtual method responsible for writing to the stream. More...
 
void resize (uint64_t newSize)
 Resizes the internal buffer size. More...
 
template<bool EXISTING_OBJ>
void internal_ReadObject (CSerializablePtr &newObj, CSerializable *existingObj=NULL)
 A common template code for both versions of CStream::ReadObject() More...
 

Protected Attributes

void_ptr_noncopy m_memory
 Internal data. More...
 
uint64_t m_size
 
uint64_t m_position
 
uint64_t m_bytesWritten
 
uint64_t m_alloc_block_size
 
bool m_read_only
 If the memory block does not belong to the object. More...
 

Member Enumeration Documentation

◆ TSeekOrigin

Used in CStream::Seek.

Enumerator
sFromBeginning 
sFromCurrent 
sFromEnd 

Definition at line 42 of file CStream.h.

Constructor & Destructor Documentation

◆ CMemoryStream() [1/2]

CMemoryStream::CMemoryStream ( )

Default constructor.

Definition at line 25 of file CMemoryStream.cpp.

◆ CMemoryStream() [2/2]

CMemoryStream::CMemoryStream ( const void data,
const uint64_t  nBytesInData 
)

Constructor to initilize the data in the stream from a block of memory (which is copied), and sets the current stream position at the beginning of the data.

See also
assignMemoryNotOwn

Definition at line 38 of file CMemoryStream.cpp.

References ASSERT_, mrpt::utils::non_copiable_ptr_basic< T >::get(), m_bytesWritten, m_memory, mrpt::system::os::memcpy(), MRPT_END, MRPT_START, and resize().

◆ ~CMemoryStream()

CMemoryStream::~CMemoryStream ( )
virtual

Destructor.

Definition at line 76 of file CMemoryStream.cpp.

References m_read_only, and resize().

Member Function Documentation

◆ assignMemoryNotOwn()

void CMemoryStream::assignMemoryNotOwn ( const void data,
const uint64_t  nBytesInData 
)

Initilize the data in the stream from a block of memory which is NEITHER OWNED NOR COPIED by the object, so it must exist during the whole live of the object.

After assigning a block of data with this method, the object becomes "read-only", so further attempts to change the size of the buffer will raise an exception. This method resets the write and read positions to the beginning.

Definition at line 63 of file CMemoryStream.cpp.

References Clear(), m_bytesWritten, m_memory, m_position, m_read_only, m_size, and mrpt::utils::non_copiable_ptr_basic< T >::set().

Referenced by mrpt::utils::mrpt_recv_from_zmq_buf(), mrpt::utils::OctetVectorToObject(), and mrpt::utils::RawStringToObject().

◆ changeSize()

void CMemoryStream::changeSize ( uint64_t  newSize)

Change size. This would be rarely used. Use ">>" operators for writing to stream.

See also
Stream

Definition at line 234 of file CMemoryStream.cpp.

References resize().

Referenced by mrpt::utils::CImage::readFromStream().

◆ Clear()

void CMemoryStream::Clear ( )

Clears the memory buffer.

Definition at line 203 of file CMemoryStream.cpp.

References m_bytesWritten, m_memory, m_position, m_read_only, m_size, and resize().

Referenced by assignMemoryNotOwn(), loadBufferFromFile(), and mrpt::utils::mrpt_recv_from_zmq_buf().

◆ getline()

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

Definition at line 680 of file CStream.cpp.

◆ getPosition()

uint64_t CMemoryStream::getPosition ( )
virtual

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 195 of file CMemoryStream.cpp.

References m_position.

◆ getRawBufferData()

void * CMemoryStream::getRawBufferData ( )

◆ getTotalBytesCount()

uint64_t CMemoryStream::getTotalBytesCount ( )
virtual

◆ internal_ReadObject()

template<bool EXISTING_OBJ>
void CStream::internal_ReadObject ( CSerializablePtr &  newObj,
CSerializable existingObj = NULL 
)
protectedinherited

◆ loadBufferFromFile()

bool CMemoryStream::loadBufferFromFile ( const std::string file_name)

◆ operator<<() [1/2]

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

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

Definition at line 211 of file CStream.cpp.

◆ operator<<() [2/2]

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

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

Definition at line 218 of file CStream.cpp.

◆ operator>>() [1/2]

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

Definition at line 224 of file CStream.cpp.

◆ operator>>() [2/2]

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

Definition at line 230 of file CStream.cpp.

◆ printf()

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

Writes a string to the stream in a textual form.

See also
CStdOutStream

Definition at line 507 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::CObservationGPS::dumpToStream(), mrpt::obs::gnss::Message_NMEA_VTG::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NMEA_ZDA::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::dumpToStream(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::maps::TMetricMapInitializer::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::dumpToTextStream(), mrpt::slam::CIncrementalMapPartitioner::TOptions::dumpToTextStream(), mrpt::slam::CICP::TConfigParams::dumpToTextStream(), mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_FabMap::TOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::dumpToTextStream(), mrpt::vision::CFeatureExtraction::TOptions::dumpToTextStream(), mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::utils::CLoadableOptions::dumpToTextStream(), mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TInsertionOptions::dumpToTextStream(), mrpt::bayes::CParticleFilter::TParticleFilterOptions::dumpToTextStream(), mrpt::slam::CGridMapAligner::TConfigParams::dumpToTextStream(), mrpt::graphslam::TSlidingWindow::dumpToTextStream(), mrpt::maps::CHeightGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TLikelihoodOptions::dumpToTextStream(), mrpt::maps::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream(), mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TInsertionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TLikelihoodOptions::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM::TOptions::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::dumpToTextStream(), mrpt::maps::CPointsMap::TInsertionOptions::dumpToTextStream(), mrpt::vision::TStereoSystemParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::vision::CFeature::dumpToTextStream(), mrpt::maps::CLandmarksMap::TInsertionOptions::dumpToTextStream(), mrpt::maps::CPointsMap::TLikelihoodOptions::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::dumpToTextStream(), mrpt::maps::CColouredPointsMap::TColourOptions::dumpToTextStream(), mrpt::maps::CLandmarksMap::TLikelihoodOptions::dumpToTextStream(), mrpt::maps::TSetOfMetricMapInitializers::dumpToTextStream(), mrpt::vision::TMatchingOptions::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::hmtslam::CHMTSLAM::TOptions::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::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(), mrpt::synch::CCriticalSection::enter(), generic_dump_BESTPOS(), generic_dump_MARKTIME(), mrpt::maps::CRandomFieldGridMap2D::TInsertionOptionsCommon::internal_dumpToTextStream_common(), mrpt::synch::CCriticalSection::leave(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetObservationsAndDataAssociation(), mrpt::maps::CRandomFieldGridMap3D::saveAsCSV(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), mrpt::utils::CTimeLogger::saveToCSVFile(), and mrpt::poses::CPoseInterpolatorBase< 3 >::saveToTextFile().

◆ printf_vector()

template<typename CONTAINER_TYPE >
virtual int void mrpt::utils::CStream::printf_vector ( const char *  fmt,
const CONTAINER_TYPE &  V,
char  separator = ',' 
)
inlineinherited

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

Template Parameters
CONTAINER_TYPEcan be any vector<T>, deque<T> or alike.

Definition at line 208 of file CStream.h.

Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel().

◆ Read()

size_t CMemoryStream::Read ( void Buffer,
size_t  Count 
)
protectedvirtual

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

Implements mrpt::utils::CStream.

Definition at line 118 of file CMemoryStream.cpp.

References mrpt::utils::non_copiable_ptr_basic< T >::get(), m_memory, m_position, m_size, mrpt::system::os::memcpy(), and min.

◆ ReadAsAndCastTo()

template<typename STORED_TYPE , typename CAST_TO_TYPE >
void mrpt::utils::CStream::ReadAsAndCastTo ( CAST_TO_TYPE &  read_here)
inlineinherited

Read a value from a stream stored in a type different of the target variable, making the conversion via static_cast.

Useful for coding backwards compatible de-serialization blocks

Definition at line 194 of file CStream.h.

◆ ReadBuffer()

size_t 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,

Definition at line 45 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(), loadBufferFromFile(), and mrpt::hwdrivers::CHokuyoURG::purgeBuffers().

◆ 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:
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 95 of file CStream.h.

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

Referenced by mrpt::math::operator>>(), and triangle_readFromStream().

◆ 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 113 of file CStream.h.

◆ ReadObject() [1/2]

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

Definition at line 486 of file CStream.cpp.

Referenced by mrpt::utils::mrpt_recv_from_zmq(), mrpt::utils::mrpt_recv_from_zmq_into(), mrpt::utils::OctetVectorToObject(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::utils::RawStringToObject(), mrpt::utils::StringToObject(), and TEST().

◆ ReadObject() [2/2]

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

Definition at line 498 of file CStream.cpp.

◆ receiveMessage()

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

◆ resize()

void CMemoryStream::resize ( uint64_t  newSize)
protected

◆ saveBufferToFile()

bool CMemoryStream::saveBufferToFile ( const std::string file_name)

Saves the entire buffer to a file.

Returns
true on success, false on error

Definition at line 242 of file CMemoryStream.cpp.

References mrpt::utils::non_copiable_ptr_basic< T >::get(), getTotalBytesCount(), m_memory, and mrpt::utils::CStream::WriteBuffer().

◆ Seek()

uint64_t CMemoryStream::Seek ( int64_t  Offset,
CStream::TSeekOrigin  Origin = sFromBeginning 
)
virtual

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.

Implements mrpt::utils::CStream.

Definition at line 164 of file CMemoryStream.cpp.

References m_bytesWritten, m_position, m_size, mrpt::utils::CStream::sFromBeginning, mrpt::utils::CStream::sFromCurrent, and mrpt::utils::CStream::sFromEnd.

Referenced by mrpt::obs::gnss::gnss_message_ptr::gnss_message_ptr(), mrpt::hwdrivers::CGPSInterface::implement_parser_NOVATEL_OEM6(), mrpt::utils::mrpt_recv_from_zmq_buf(), mrpt::obs::gnss::gnss_message_ptr::operator=(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::utils::CImage::readFromStream(), mrpt::utils::StringToObject(), TEST(), and GraphTester< my_graph_t >::test_graph_bin_serialization().

◆ sendMessage()

void 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

Definition at line 556 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().

◆ setAllocBlockSize()

void mrpt::utils::CMemoryStream::setAllocBlockSize ( uint64_t  alloc_block_size)
inline

Change the size of the additional memory block that is reserved whenever the current block runs too short (default=0x10000 bytes)

Definition at line 73 of file CMemoryStream.h.

References ASSERT_.

◆ Write()

size_t CMemoryStream::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.

Definition at line 137 of file CMemoryStream.cpp.

References mrpt::utils::non_copiable_ptr_basic< T >::get(), m_alloc_block_size, m_bytesWritten, m_memory, m_position, m_size, mrpt::system::os::memcpy(), and resize().

◆ WriteBuffer()

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

Definition at line 67 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::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), empty_output_buffer(), 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<<(), saveBufferToFile(), mrpt::hwdrivers::CHokuyoURG::sendCmd(), mrpt::hwdrivers::CGPSInterface::sendCustomCommand(), mrpt::hwdrivers::CBoardENoses::setActiveChamber(), mrpt::utils::StringToObject(), term_destination(), mrpt::system::vectorToBinaryFile(), mrpt::nav::CLogFileRecord::writeToStream(), mrpt::maps::CHeightGridMap2D_MRF::writeToStream(), mrpt::maps::CGasConcentrationGridMap2D::writeToStream(), mrpt::maps::CWirelessPowerGridMap2D::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::maps::CReflectivityGridMap2D::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), mrpt::maps::COccupancyGridMap2D::writeToStream(), mrpt::maps::CRandomFieldGridMap3D::writeToStream(), mrpt::utils::CImage::writeToStream(), and mrpt::opengl::CRenderizable::writeToStreamRender().

◆ 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 139 of file CStream.h.

Referenced by triangle_writeToStream(), mrpt::math::CMatrix::writeToStream(), mrpt::math::CMatrixD::writeToStream(), mrpt::maps::CColouredPointsMap::writeToStream(), mrpt::maps::CWeightedPointsMap::writeToStream(), mrpt::maps::CSimplePointsMap::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::maps::COccupancyGridMap2D::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().

◆ WriteObject()

void CStream::WriteObject ( const CSerializable o)
inherited

Member Data Documentation

◆ m_alloc_block_size

uint64_t mrpt::utils::CMemoryStream::m_alloc_block_size
protected

Definition at line 35 of file CMemoryStream.h.

Referenced by Write().

◆ m_bytesWritten

uint64_t mrpt::utils::CMemoryStream::m_bytesWritten
protected

◆ m_memory

void_ptr_noncopy mrpt::utils::CMemoryStream::m_memory
protected

◆ m_position

uint64_t mrpt::utils::CMemoryStream::m_position
protected

◆ m_read_only

bool mrpt::utils::CMemoryStream::m_read_only
protected

If the memory block does not belong to the object.

Definition at line 36 of file CMemoryStream.h.

Referenced by assignMemoryNotOwn(), Clear(), resize(), and ~CMemoryStream().

◆ m_size

uint64_t mrpt::utils::CMemoryStream::m_size
protected

Definition at line 34 of file CMemoryStream.h.

Referenced by assignMemoryNotOwn(), Clear(), Read(), resize(), Seek(), and Write().




Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019