Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Member Functions | Static 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 type with that name to allow backward compatibility.
See also
CSensoryFrame, CPosePDF

Definition at line 35 of file CSimpleMap.h.

#include <mrpt/maps/CSimpleMap.h>

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

Public Member Functions

voidoperator new (size_t size)
 
voidoperator new[] (size_t size)
 
void operator delete (void *ptr) noexcept
 
void operator delete[] (void *ptr) noexcept
 
void operator delete (void *memory, void *ptr) noexcept
 
voidoperator new (size_t size, const std::nothrow_t &) noexcept
 
void operator delete (void *ptr, const std::nothrow_t &) noexcept
 
 CSimpleMap ()=default
 Default constructor (empty map) More...
 
 CSimpleMap (const CSimpleMap &o)
 Copy constructor. More...
 
CSimpleMapoperator= (const CSimpleMap &o)
 Copy. More...
 
virtual mxArraywriteToMatlab () const
 Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More...
 
Map access and modification
bool saveToFile (const std::string &filName) const
 Save this object to a .simplemap binary file (compressed with gzip) More...
 
bool loadFromFile (const std::string &filName)
 Load the contents of this object from a .simplemap binary file (possibly compressed with gzip) More...
 
size_t size () const
 Returns the count of pairs (pose,sensory data) More...
 
bool empty () const
 Returns size()!=0. More...
 
void get (size_t index, mrpt::poses::CPose3DPDF::Ptr &out_posePDF, mrpt::obs::CSensoryFrame::Ptr &out_SF) const
 Access to the i'th pair, first one is index '0'. More...
 
void set (size_t index, const mrpt::poses::CPose3DPDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Changes the i'th pair, first one is index '0'. More...
 
void set (size_t index, const mrpt::poses::CPosePDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Changes the i'th pair, first one is index '0'. More...
 
void remove (size_t index)
 Deletes the i'th pair, first one is index '0'. More...
 
void insert (const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
 Add a new pair to the sequence. More...
 
void insert (const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique). More...
 
void insert (const mrpt::poses::CPose3DPDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique). More...
 
void insertToPos (size_t index, const mrpt::poses::CPose3DPDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Insert a new pair to the sequence, making a copy of the smart pointer (it's not made unique) to. More...
 
void insert (const mrpt::poses::CPosePDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Add a new pair to the sequence. More...
 
void insert (const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
 Add a new pair to the sequence. More...
 
void insert (const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
 Add a new pair to the sequence. More...
 
void clear ()
 Remove all stored pairs. More...
 
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. More...
 

Static Public Member Functions

static voidoperator new (size_t size, void *ptr)
 

Protected Member Functions

CSerializable virtual methods
uint8_t serializeGetVersion () const override
 Must return the current versioning number of the object. More...
 
void serializeTo (mrpt::serialization::CArchive &out) const override
 Pure virtual method for writing (serializing) to an abstract archive. More...
 
void serializeFrom (mrpt::serialization::CArchive &in, uint8_t serial_version) override
 Pure virtual method for reading (deserializing) from an abstract archive. More...
 

Private Attributes

TPosePDFSensFramePairList m_posesObsPairs
 The stored data. More...
 

RTTI stuff


using Ptr = std::shared_ptr< CSimpleMap >
 
using ConstPtr = std::shared_ptr< const CSimpleMap >
 
using UniquePtr = std::unique_ptr< CSimpleMap >
 
using ConstUniquePtr = std::unique_ptr< const CSimpleMap >
 
static mrpt::rtti::CLASSINIT _init_CSimpleMap
 
static const mrpt::rtti::TRuntimeClassId runtimeClassId
 
static constexpr const char * className = "CSimpleMap"
 
static const mrpt::rtti::TRuntimeClassId_GetBaseClass ()
 
static constexpr auto getClassName ()
 
static const mrpt::rtti::TRuntimeClassIdGetRuntimeClassIdStatic ()
 
static mrpt::rtti::CObjectCreateObject ()
 
template<typename... Args>
static Ptr Create (Args &&... args)
 
template<typename... Args>
static UniquePtr CreateUnique (Args &&... args)
 
virtual const mrpt::rtti::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::rtti::CObjectclone () const override
 Returns a deep copy (clone) of the object, indepently of its class. More...
 

Iterators API

using TPosePDFSensFramePair = std::pair< mrpt::poses::CPose3DPDF::Ptr, mrpt::obs::CSensoryFrame::Ptr >
 
using TPosePDFSensFramePairList = std::deque< TPosePDFSensFramePair >
 
using const_iterator = TPosePDFSensFramePairList::const_iterator
 
using iterator = TPosePDFSensFramePairList::iterator
 
using reverse_iterator = TPosePDFSensFramePairList::reverse_iterator
 
using const_reverse_iterator = TPosePDFSensFramePairList::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

using mrpt::maps::CSimpleMap::const_iterator = TPosePDFSensFramePairList::const_iterator

Definition at line 182 of file CSimpleMap.h.

◆ const_reverse_iterator

using mrpt::maps::CSimpleMap::const_reverse_iterator = TPosePDFSensFramePairList::const_reverse_iterator

Definition at line 186 of file CSimpleMap.h.

◆ ConstPtr

using mrpt::maps::CSimpleMap::ConstPtr = std::shared_ptr<const CSimpleMap >

Definition at line 37 of file CSimpleMap.h.

◆ ConstUniquePtr

using mrpt::maps::CSimpleMap::ConstUniquePtr = std::unique_ptr<const CSimpleMap >

Definition at line 37 of file CSimpleMap.h.

◆ iterator

using mrpt::maps::CSimpleMap::iterator = TPosePDFSensFramePairList::iterator

Definition at line 183 of file CSimpleMap.h.

◆ Ptr

using mrpt::maps::CSimpleMap::Ptr = std::shared_ptr< CSimpleMap >

A type for the associated smart pointer

Definition at line 37 of file CSimpleMap.h.

◆ reverse_iterator

using mrpt::maps::CSimpleMap::reverse_iterator = TPosePDFSensFramePairList::reverse_iterator

Definition at line 184 of file CSimpleMap.h.

◆ TPosePDFSensFramePair

Definition at line 179 of file CSimpleMap.h.

◆ TPosePDFSensFramePairList

Definition at line 180 of file CSimpleMap.h.

◆ UniquePtr

using mrpt::maps::CSimpleMap::UniquePtr = std::unique_ptr< CSimpleMap >

Definition at line 37 of file CSimpleMap.h.

Constructor & Destructor Documentation

◆ CSimpleMap() [1/2]

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

Default constructor (empty map)

◆ CSimpleMap() [2/2]

CSimpleMap::CSimpleMap ( const CSimpleMap o)

Copy constructor.

Definition at line 34 of file CSimpleMap.cpp.

References fn_pair_make_unique, and m_posesObsPairs.

Member Function Documentation

◆ _GetBaseClass()

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

◆ begin() [1/2]

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

Definition at line 190 of file CSimpleMap.h.

References m_posesObsPairs.

◆ begin() [2/2]

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

Definition at line 188 of file CSimpleMap.h.

References m_posesObsPairs.

◆ changeCoordinatesOrigin()

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

Definition at line 260 of file CSimpleMap.cpp.

References m_posesObsPairs.

◆ clear()

void CSimpleMap::clear ( )

◆ clone()

virtual mrpt::rtti::CObject* mrpt::maps::CSimpleMap::clone ( ) const
overridevirtual

Returns a deep copy (clone) of the object, indepently of its class.

Implements mrpt::rtti::CObject.

◆ Create()

template<typename... Args>
static Ptr mrpt::maps::CSimpleMap::Create ( Args &&...  args)
inlinestatic

Definition at line 37 of file CSimpleMap.h.

◆ CreateObject()

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

◆ CreateUnique()

template<typename... Args>
static UniquePtr mrpt::maps::CSimpleMap::CreateUnique ( Args &&...  args)
inlinestatic

Definition at line 37 of file CSimpleMap.h.

◆ duplicateGetSmartPtr()

mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr ( ) const
inlineinherited

Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).

Definition at line 169 of file CObject.h.

References mrpt::rtti::CObject::clone().

Referenced by mrpt::obs::CRawlog::addActions(), and mrpt::obs::CRawlog::addObservations().

◆ empty()

bool CSimpleMap::empty ( ) const

◆ end() [1/2]

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

Definition at line 191 of file CSimpleMap.h.

References m_posesObsPairs.

◆ end() [2/2]

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

Definition at line 189 of file CSimpleMap.h.

References m_posesObsPairs.

◆ get()

void CSimpleMap::get ( size_t  index,
mrpt::poses::CPose3DPDF::Ptr out_posePDF,
mrpt::obs::CSensoryFrame::Ptr 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 nullptr pointer if you dont need one of the two variables to be returned.

Exceptions
std::exceptionOn index out of bounds.

Definition at line 56 of file CSimpleMap.cpp.

References m_posesObsPairs, and THROW_EXCEPTION.

Referenced by mrpt::hmtslam::CLocalMetricHypothesis::changeCoordinateOrigin(), mrpt::maps::CMultiMetricMapPDF::clear(), mrpt::slam::CRangeBearingKFSLAM::getAs3DObject(), mrpt::slam::CRangeBearingKFSLAM::getLastPartitionLandmarks(), mrpt::slam::CMetricMapBuilderICP::initialize(), mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations(), mrpt::slam::CRangeBearingKFSLAM2D::saveMapAndPath2DRepresentationAsMATLABFile(), and mrpt::slam::CRangeBearingKFSLAM::saveMapAndPath2DRepresentationAsMATLABFile().

◆ getClassName()

static constexpr auto mrpt::maps::CSimpleMap::getClassName ( )
inlinestaticconstexpr

Definition at line 37 of file CSimpleMap.h.

◆ GetRuntimeClass()

virtual const mrpt::rtti::TRuntimeClassId* mrpt::maps::CSimpleMap::GetRuntimeClass ( ) const
overridevirtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::serialization::CSerializable.

◆ GetRuntimeClassIdStatic()

static const mrpt::rtti::TRuntimeClassId& mrpt::maps::CSimpleMap::GetRuntimeClassIdStatic ( )
static

◆ insert() [1/6]

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

◆ insert() [2/6]

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

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

Definition at line 100 of file CSimpleMap.cpp.

References mrpt::rtti::CObject::clone(), m_posesObsPairs, MRPT_END, and MRPT_START.

◆ insert() [3/6]

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

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

Definition at line 118 of file CSimpleMap.cpp.

References m_posesObsPairs, MRPT_END, and MRPT_START.

◆ insert() [4/6]

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

Definition at line 154 of file CSimpleMap.cpp.

References mrpt::rtti::CObject::clone(), m_posesObsPairs, MRPT_END, and MRPT_START.

◆ insert() [5/6]

void CSimpleMap::insert ( const mrpt::poses::CPosePDF in_posePDF,
const mrpt::obs::CSensoryFrame::Ptr 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.

Definition at line 171 of file CSimpleMap.cpp.

References mrpt::rtti::CObject::clone(), m_posesObsPairs, MRPT_END, and MRPT_START.

◆ insert() [6/6]

void CSimpleMap::insert ( const mrpt::poses::CPosePDF::Ptr in_posePDF,
const mrpt::obs::CSensoryFrame::Ptr 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.

Definition at line 189 of file CSimpleMap.cpp.

References insert().

◆ insertToPos()

void CSimpleMap::insertToPos ( size_t  index,
const mrpt::poses::CPose3DPDF::Ptr in_posePDF,
const mrpt::obs::CSensoryFrame::Ptr in_SF 
)

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

Parameters
indexPosition in the simplemap where new element will be inserted to

Definition at line 195 of file CSimpleMap.cpp.

References m_posesObsPairs, MRPT_END, and MRPT_START.

◆ loadFromFile()

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

Definition at line 290 of file CSimpleMap.cpp.

References mrpt::serialization::archiveFrom().

◆ operator delete() [1/3]

void mrpt::maps::CSimpleMap::operator delete ( void memory,
void ptr 
)
inlinenoexcept

Definition at line 37 of file CSimpleMap.h.

◆ operator delete() [2/3]

void mrpt::maps::CSimpleMap::operator delete ( void ptr)
inlinenoexcept

Definition at line 37 of file CSimpleMap.h.

◆ operator delete() [3/3]

void mrpt::maps::CSimpleMap::operator delete ( void ptr,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 37 of file CSimpleMap.h.

◆ operator delete[]()

void mrpt::maps::CSimpleMap::operator delete[] ( void ptr)
inlinenoexcept

Definition at line 37 of file CSimpleMap.h.

◆ operator new() [1/3]

void* mrpt::maps::CSimpleMap::operator new ( size_t  size)
inline

Definition at line 37 of file CSimpleMap.h.

◆ operator new() [2/3]

void* mrpt::maps::CSimpleMap::operator new ( size_t  size,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 37 of file CSimpleMap.h.

◆ operator new() [3/3]

static void* mrpt::maps::CSimpleMap::operator new ( size_t  size,
void ptr 
)
inlinestatic

Definition at line 37 of file CSimpleMap.h.

◆ operator new[]()

void* mrpt::maps::CSimpleMap::operator new[] ( size_t  size)
inline

Definition at line 37 of file CSimpleMap.h.

◆ operator=()

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

Copy.

Definition at line 40 of file CSimpleMap.cpp.

References fn_pair_make_unique, m_posesObsPairs, MRPT_END, and MRPT_START.

◆ rbegin() [1/2]

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

Definition at line 200 of file CSimpleMap.h.

References m_posesObsPairs.

◆ rbegin() [2/2]

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

Definition at line 192 of file CSimpleMap.h.

References m_posesObsPairs.

Referenced by mrpt::slam::CMetricMapBuilderRBPF::initialize().

◆ remove()

void 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

Definition at line 65 of file CSimpleMap.cpp.

References m_posesObsPairs, MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ rend() [1/2]

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

Definition at line 201 of file CSimpleMap.h.

References m_posesObsPairs.

◆ rend() [2/2]

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

Definition at line 196 of file CSimpleMap.h.

References m_posesObsPairs.

◆ saveToFile()

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

Definition at line 271 of file CSimpleMap.cpp.

References mrpt::serialization::archiveFrom().

◆ serializeFrom()

void CSimpleMap::serializeFrom ( mrpt::serialization::CArchive in,
uint8_t  serial_version 
)
overrideprotectedvirtual

Pure virtual method for reading (deserializing) from an abstract archive.

Users don't call this method directly. Instead, use stream >> object;.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any I/O error

Implements mrpt::serialization::CSerializable.

Definition at line 221 of file CSimpleMap.cpp.

References clear(), m_posesObsPairs, and MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION.

◆ serializeGetVersion()

uint8_t CSimpleMap::serializeGetVersion ( ) const
overrideprotectedvirtual

Must return the current versioning number of the object.

Start in zero for new classes, and increments each time there is a change in the stored format.

Implements mrpt::serialization::CSerializable.

Definition at line 214 of file CSimpleMap.cpp.

◆ serializeTo()

void CSimpleMap::serializeTo ( mrpt::serialization::CArchive out) const
overrideprotectedvirtual

Pure virtual method for writing (serializing) to an abstract archive.

Users don't call this method directly. Instead, use stream << object;.

Exceptions
std::exceptionOn any I/O error

Implements mrpt::serialization::CSerializable.

Definition at line 215 of file CSimpleMap.cpp.

References m_posesObsPairs, and mrpt::serialization::CArchive::WriteAs().

◆ set() [1/2]

void CSimpleMap::set ( size_t  index,
const mrpt::poses::CPose3DPDF::Ptr in_posePDF,
const mrpt::obs::CSensoryFrame::Ptr 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 nullptr, 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

Definition at line 73 of file CSimpleMap.cpp.

References m_posesObsPairs, MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ set() [2/2]

void CSimpleMap::set ( size_t  index,
const mrpt::poses::CPosePDF::Ptr in_posePDF,
const mrpt::obs::CSensoryFrame::Ptr 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 nullptr, 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

Definition at line 84 of file CSimpleMap.cpp.

References m_posesObsPairs, MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ size()

size_t CSimpleMap::size ( ) const

◆ writeToMatlab()

virtual mxArray* mrpt::serialization::CSerializable::writeToMatlab ( ) const
inlinevirtualinherited

Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.

Returns
A new mxArray (caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB.

Definition at line 70 of file CSerializable.h.

Member Data Documentation

◆ _init_CSimpleMap

mrpt::rtti::CLASSINIT mrpt::maps::CSimpleMap::_init_CSimpleMap
staticprotected

Definition at line 37 of file CSimpleMap.h.

◆ className

constexpr const char* mrpt::maps::CSimpleMap::className = "CSimpleMap"
staticconstexpr

Definition at line 37 of file CSimpleMap.h.

◆ m_posesObsPairs

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

◆ runtimeClassId

const mrpt::rtti::TRuntimeClassId mrpt::maps::CSimpleMap::runtimeClassId
staticprotected

Definition at line 37 of file CSimpleMap.h.




Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST