Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Public Member Functions | Private Attributes
mrpt::maps::CSimpleMap Class Reference

Detailed Description

This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be totally determined with this information.

The pose of the sensory frame is not deterministic, but described by some PDF. Full 6D poses are used.

Note
Objects of this class are serialized into (possibly GZ-compressed) files with the extension ".simplemap".
Before MRPT 0.9.0 the name of this class was "CSensFrameProbSequence", that's why there is a typedef with that name to allow backward compatibility.
See also
CSensoryFrame, CPosePDF

Definition at line 34 of file maps/CSimpleMap.h.

#include <mrpt/maps/CSimpleMap.h>

Inheritance diagram for mrpt::maps::CSimpleMap:
Inheritance graph

Public Member Functions

 CSimpleMap ()
 Default constructor (empty map)
 
 CSimpleMap (const CSimpleMap &o)
 Copy constructor.
 
virtual ~CSimpleMap ()
 Destructor:
 
CSimpleMapoperator= (const CSimpleMap &o)
 Copy.
 
Map access and modification
bool saveToFile (const std::string &filName) const
 Save this object to a .simplemap binary file (compressed with gzip)
 
bool loadFromFile (const std::string &filName)
 Load the contents of this object from a .simplemap binary file (possibly compressed with gzip)
 
size_t size () const
 Returns the count of pairs (pose,sensory data)
 
bool empty () const
 Returns size()!=0.
 
void get (size_t index, mrpt::poses::CPose3DPDFPtr &out_posePDF, mrpt::obs::CSensoryFramePtr &out_SF) const
 Access to the i'th pair, first one is index '0'.
 
void set (size_t index, const mrpt::poses::CPose3DPDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF)
 Changes the i'th pair, first one is index '0'.
 
void set (size_t index, const mrpt::poses::CPosePDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF)
 Changes the i'th pair, first one is index '0'.
 
void remove (size_t index)
 Deletes the i'th pair, first one is index '0'.
 
void insert (const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
 Add a new pair to the sequence.
 
void insert (const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF)
 Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique).
 
void insert (const mrpt::poses::CPose3DPDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF)
 Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique).
 
void insert (const mrpt::poses::CPosePDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF)
 Add a new pair to the sequence.
 
void insert (const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
 Add a new pair to the sequence.
 
void insert (const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF)
 Add a new pair to the sequence.
 
void clear ()
 Remove all stored pairs.
 
void changeCoordinatesOrigin (const mrpt::poses::CPose3D &newOrigin)
 Change the coordinate origin of all stored poses, for consistency with future new poses to enter in the system.
 

Protected Member Functions

CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const MRPT_OVERRIDE
 
void readFromStream (mrpt::utils::CStream &in, int version) MRPT_OVERRIDE
 

Private Attributes

TPosePDFSensFramePairList m_posesObsPairs
 The stored data.
 

RTTI stuff <br>

typedef CSimpleMapPtr SmartPtr
 
static mrpt::utils::CLASSINIT _init_CSimpleMap
 
static mrpt::utils::TRuntimeClassId classCSimpleMap
 
static const mrpt::utils::TRuntimeClassIdclassinfo
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const MRPT_OVERRIDE
 
virtual mrpt::utils::CObjectduplicate () const MRPT_OVERRIDE
 
static mrpt::utils::CObjectCreateObject ()
 
static CSimpleMapPtr Create ()
 

Iterators API

typedef std::pair< mrpt::poses::CPose3DPDFPtr, mrpt::obs::CSensoryFramePtrTPosePDFSensFramePair
 
typedef std::deque< TPosePDFSensFramePairTPosePDFSensFramePairList
 
typedef TPosePDFSensFramePairList::const_iterator const_iterator
 
typedef TPosePDFSensFramePairList::iterator iterator
 
typedef TPosePDFSensFramePairList::reverse_iterator reverse_iterator
 
typedef TPosePDFSensFramePairList::const_reverse_iterator const_reverse_iterator
 
const_iterator begin () const
 
const_iterator end () const
 
iterator begin ()
 
iterator end ()
 
const_reverse_iterator rbegin () const
 
const_reverse_iterator rend () const
 
reverse_iterator rbegin ()
 
reverse_iterator rend ()
 

Member Typedef Documentation

◆ const_iterator

typedef TPosePDFSensFramePairList::const_iterator mrpt::maps::CSimpleMap::const_iterator

Definition at line 130 of file maps/CSimpleMap.h.

◆ const_reverse_iterator

typedef TPosePDFSensFramePairList::const_reverse_iterator mrpt::maps::CSimpleMap::const_reverse_iterator

Definition at line 133 of file maps/CSimpleMap.h.

◆ iterator

typedef TPosePDFSensFramePairList::iterator mrpt::maps::CSimpleMap::iterator

Definition at line 131 of file maps/CSimpleMap.h.

◆ reverse_iterator

typedef TPosePDFSensFramePairList::reverse_iterator mrpt::maps::CSimpleMap::reverse_iterator

Definition at line 132 of file maps/CSimpleMap.h.

◆ SmartPtr

A typedef for the associated smart pointer

Definition at line 37 of file maps/CSimpleMap.h.

◆ TPosePDFSensFramePair

Definition at line 127 of file maps/CSimpleMap.h.

◆ TPosePDFSensFramePairList

Definition at line 128 of file maps/CSimpleMap.h.

Constructor & Destructor Documentation

◆ CSimpleMap() [1/2]

mrpt::maps::CSimpleMap::CSimpleMap ( )

Default constructor (empty map)

◆ CSimpleMap() [2/2]

mrpt::maps::CSimpleMap::CSimpleMap ( const CSimpleMap o)

Copy constructor.

◆ ~CSimpleMap()

virtual mrpt::maps::CSimpleMap::~CSimpleMap ( )
virtual

Destructor:

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId * mrpt::maps::CSimpleMap::_GetBaseClass ( )
staticprotected

◆ begin() [1/2]

iterator mrpt::maps::CSimpleMap::begin ( )
inline

Definition at line 137 of file maps/CSimpleMap.h.

◆ begin() [2/2]

const_iterator mrpt::maps::CSimpleMap::begin ( ) const
inline

Definition at line 135 of file maps/CSimpleMap.h.

◆ changeCoordinatesOrigin()

void mrpt::maps::CSimpleMap::changeCoordinatesOrigin ( const mrpt::poses::CPose3D newOrigin)

Change the coordinate origin of all stored poses, for consistency with future new poses to enter in the system.

◆ clear()

void mrpt::maps::CSimpleMap::clear ( )

Remove all stored pairs.

See also
remove

◆ Create()

static CSimpleMapPtr mrpt::maps::CSimpleMap::Create ( )
static

◆ CreateObject()

static mrpt::utils::CObject * mrpt::maps::CSimpleMap::CreateObject ( )
static

◆ duplicate()

virtual mrpt::utils::CObject * mrpt::maps::CSimpleMap::duplicate ( ) const
virtual

◆ empty()

bool mrpt::maps::CSimpleMap::empty ( ) const

Returns size()!=0.

◆ end() [1/2]

iterator mrpt::maps::CSimpleMap::end ( )
inline

Definition at line 138 of file maps/CSimpleMap.h.

◆ end() [2/2]

const_iterator mrpt::maps::CSimpleMap::end ( ) const
inline

Definition at line 136 of file maps/CSimpleMap.h.

◆ get()

void mrpt::maps::CSimpleMap::get ( size_t  index,
mrpt::poses::CPose3DPDFPtr out_posePDF,
mrpt::obs::CSensoryFramePtr out_SF 
) const

Access to the i'th pair, first one is index '0'.

NOTE: This method returns pointers to the objects inside the list, nor a copy of them, so do neither modify them nor delete them. NOTE: You can pass a NULL pointer if you dont need one of the two variables to be returned.

Exceptions
std::exceptionOn index out of bounds.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId * mrpt::maps::CSimpleMap::GetRuntimeClass ( ) const
virtual

◆ insert() [1/6]

void mrpt::maps::CSimpleMap::insert ( const mrpt::poses::CPose3DPDF in_posePDF,
const mrpt::obs::CSensoryFrame in_SF 
)

Add a new pair to the sequence.

The objects are copied, so original ones can be free if desired after insertion.

◆ insert() [2/6]

void mrpt::maps::CSimpleMap::insert ( const mrpt::poses::CPose3DPDF in_posePDF,
const mrpt::obs::CSensoryFramePtr in_SF 
)

Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique).

◆ insert() [3/6]

void mrpt::maps::CSimpleMap::insert ( const mrpt::poses::CPose3DPDFPtr in_posePDF,
const mrpt::obs::CSensoryFramePtr in_SF 
)

Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique).

◆ insert() [4/6]

void mrpt::maps::CSimpleMap::insert ( const mrpt::poses::CPosePDF in_posePDF,
const mrpt::obs::CSensoryFrame in_SF 
)

Add a new pair to the sequence.

The objects are copied, so original ones can be free if desired after insertion. This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.

◆ insert() [5/6]

void mrpt::maps::CSimpleMap::insert ( const mrpt::poses::CPosePDF in_posePDF,
const mrpt::obs::CSensoryFramePtr in_SF 
)

Add a new pair to the sequence.

The objects are copied, so original ones can be free if desired after insertion. This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.

◆ insert() [6/6]

void mrpt::maps::CSimpleMap::insert ( const mrpt::poses::CPosePDFPtr in_posePDF,
const mrpt::obs::CSensoryFramePtr in_SF 
)

Add a new pair to the sequence.

The objects are copied, so original ones can be free if desired after insertion. This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.

◆ loadFromFile()

bool mrpt::maps::CSimpleMap::loadFromFile ( const std::string &  filName)

Load the contents of this object from a .simplemap binary file (possibly compressed with gzip)

See also
saveToFile
Returns
false on any error.

◆ operator=()

CSimpleMap & mrpt::maps::CSimpleMap::operator= ( const CSimpleMap o)

Copy.

◆ rbegin() [1/2]

reverse_iterator mrpt::maps::CSimpleMap::rbegin ( )
inline

Definition at line 142 of file maps/CSimpleMap.h.

◆ rbegin() [2/2]

const_reverse_iterator mrpt::maps::CSimpleMap::rbegin ( ) const
inline

Definition at line 140 of file maps/CSimpleMap.h.

◆ readFromStream()

void mrpt::maps::CSimpleMap::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protected

◆ remove()

void mrpt::maps::CSimpleMap::remove ( size_t  index)

Deletes the i'th pair, first one is index '0'.

Exceptions
std::exceptionOn index out of bounds.
See also
insert, get, set

◆ rend() [1/2]

reverse_iterator mrpt::maps::CSimpleMap::rend ( )
inline

Definition at line 143 of file maps/CSimpleMap.h.

◆ rend() [2/2]

const_reverse_iterator mrpt::maps::CSimpleMap::rend ( ) const
inline

Definition at line 141 of file maps/CSimpleMap.h.

◆ saveToFile()

bool mrpt::maps::CSimpleMap::saveToFile ( const std::string &  filName) const

Save this object to a .simplemap binary file (compressed with gzip)

See also
loadFromFile
Returns
false on any error.

◆ set() [1/2]

void mrpt::maps::CSimpleMap::set ( size_t  index,
const mrpt::poses::CPose3DPDFPtr in_posePDF,
const mrpt::obs::CSensoryFramePtr in_SF 
)

Changes the i'th pair, first one is index '0'.

The referenced object is COPIED, so you can freely destroy the object passed as parameter after calling this. If one of the pointers is NULL, the corresponding contents of the current i'th pair is not modified (i.e. if you want just to modify one of the values).

Exceptions
std::exceptionOn index out of bounds.
See also
insert, get, remove

◆ set() [2/2]

void mrpt::maps::CSimpleMap::set ( size_t  index,
const mrpt::poses::CPosePDFPtr in_posePDF,
const mrpt::obs::CSensoryFramePtr in_SF 
)

Changes the i'th pair, first one is index '0'.

The referenced object is COPIED, so you can freely destroy the object passed as parameter after calling this. If one of the pointers is NULL, the corresponding contents of the current i'th pair is not modified (i.e. if you want just to modify one of the values). This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.

Exceptions
std::exceptionOn index out of bounds.
See also
insert, get, remove

◆ size()

size_t mrpt::maps::CSimpleMap::size ( ) const

Returns the count of pairs (pose,sensory data)

Referenced by mrpt::maps::CMultiMetricMapPDF::getNumberOfObservationsInSimplemap().

◆ writeToStream()

void mrpt::maps::CSimpleMap::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protected

Member Data Documentation

◆ _init_CSimpleMap

mrpt::utils::CLASSINIT mrpt::maps::CSimpleMap::_init_CSimpleMap
staticprotected

Definition at line 37 of file maps/CSimpleMap.h.

◆ classCSimpleMap

mrpt::utils::TRuntimeClassId mrpt::maps::CSimpleMap::classCSimpleMap
static

Definition at line 37 of file maps/CSimpleMap.h.

◆ classinfo

const mrpt::utils::TRuntimeClassId* mrpt::maps::CSimpleMap::classinfo
static

Definition at line 37 of file maps/CSimpleMap.h.

◆ m_posesObsPairs

TPosePDFSensFramePairList mrpt::maps::CSimpleMap::m_posesObsPairs
private

The stored data.

Definition at line 148 of file maps/CSimpleMap.h.




Page generated by Doxygen 1.9.6 for MRPT 1.4.0 SVN: at Wed Mar 22 04:35:51 UTC 2023