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.
Definition at line 34 of file maps/CSimpleMap.h.
#include <mrpt/maps/CSimpleMap.h>
Public Member Functions | |
CSimpleMap () | |
Default constructor (empty map) More... | |
CSimpleMap (const CSimpleMap &o) | |
Copy constructor. More... | |
virtual | ~CSimpleMap () |
Destructor: More... | |
CSimpleMap & | operator= (const CSimpleMap &o) |
Copy. 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::CPose3DPDFPtr &out_posePDF, mrpt::obs::CSensoryFramePtr &out_SF) const |
Access to the i'th pair, first one is index '0'. More... | |
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'. More... | |
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'. 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::CSensoryFramePtr &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::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). More... | |
void | insert (const mrpt::poses::CPosePDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &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::CSensoryFramePtr &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... | |
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. More... | |
RTTI stuff <br> | |
typedef CSimpleMapPtr | SmartPtr |
static mrpt::utils::CLASSINIT | _init_CSimpleMap |
static mrpt::utils::TRuntimeClassId | classCSimpleMap |
static const mrpt::utils::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const MRPT_OVERRIDE |
virtual mrpt::utils::CObject * | duplicate () const MRPT_OVERRIDE |
static mrpt::utils::CObject * | CreateObject () |
static CSimpleMapPtr | Create () |
Iterators API | |
typedef std::pair< mrpt::poses::CPose3DPDFPtr, mrpt::obs::CSensoryFramePtr > | TPosePDFSensFramePair |
typedef std::deque< TPosePDFSensFramePair > | TPosePDFSensFramePairList |
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 () |
typedef TPosePDFSensFramePairList::const_iterator mrpt::maps::CSimpleMap::const_iterator |
Definition at line 130 of file maps/CSimpleMap.h.
typedef TPosePDFSensFramePairList::const_reverse_iterator mrpt::maps::CSimpleMap::const_reverse_iterator |
Definition at line 133 of file maps/CSimpleMap.h.
typedef TPosePDFSensFramePairList::iterator mrpt::maps::CSimpleMap::iterator |
Definition at line 131 of file maps/CSimpleMap.h.
typedef TPosePDFSensFramePairList::reverse_iterator mrpt::maps::CSimpleMap::reverse_iterator |
Definition at line 132 of file maps/CSimpleMap.h.
A typedef for the associated smart pointer
Definition at line 37 of file maps/CSimpleMap.h.
typedef std::pair<mrpt::poses::CPose3DPDFPtr,mrpt::obs::CSensoryFramePtr> mrpt::maps::CSimpleMap::TPosePDFSensFramePair |
Definition at line 127 of file maps/CSimpleMap.h.
typedef std::deque<TPosePDFSensFramePair> mrpt::maps::CSimpleMap::TPosePDFSensFramePairList |
Definition at line 128 of file maps/CSimpleMap.h.
mrpt::maps::CSimpleMap::CSimpleMap | ( | ) |
Default constructor (empty map)
mrpt::maps::CSimpleMap::CSimpleMap | ( | const CSimpleMap & | o | ) |
Copy constructor.
|
virtual |
Destructor:
|
staticprotected |
|
inline |
Definition at line 137 of file maps/CSimpleMap.h.
|
inline |
Definition at line 135 of file maps/CSimpleMap.h.
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.
void mrpt::maps::CSimpleMap::clear | ( | ) |
Remove all stored pairs.
|
static |
|
static |
|
virtual |
bool mrpt::maps::CSimpleMap::empty | ( | ) | const |
Returns size()!=0.
|
inline |
Definition at line 138 of file maps/CSimpleMap.h.
|
inline |
Definition at line 136 of file maps/CSimpleMap.h.
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.
std::exception | On index out of bounds. |
|
virtual |
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.
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).
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).
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.
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.
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.
bool mrpt::maps::CSimpleMap::loadFromFile | ( | const std::string & | filName | ) |
Load the contents of this object from a .simplemap binary file (possibly compressed with gzip)
CSimpleMap & mrpt::maps::CSimpleMap::operator= | ( | const CSimpleMap & | o | ) |
Copy.
|
inline |
Definition at line 142 of file maps/CSimpleMap.h.
|
inline |
Definition at line 140 of file maps/CSimpleMap.h.
|
protected |
void mrpt::maps::CSimpleMap::remove | ( | size_t | index | ) |
|
inline |
Definition at line 143 of file maps/CSimpleMap.h.
|
inline |
Definition at line 141 of file maps/CSimpleMap.h.
bool mrpt::maps::CSimpleMap::saveToFile | ( | const std::string & | filName | ) | const |
Save this object to a .simplemap binary file (compressed with gzip)
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).
std::exception | On index out of bounds. |
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.
std::exception | On index out of bounds. |
size_t mrpt::maps::CSimpleMap::size | ( | ) | const |
Returns the count of pairs (pose,sensory data)
Referenced by mrpt::maps::CMultiMetricMapPDF::getNumberOfObservationsInSimplemap().
|
protected |
|
staticprotected |
Definition at line 37 of file maps/CSimpleMap.h.
|
static |
Definition at line 37 of file maps/CSimpleMap.h.
|
static |
Definition at line 37 of file maps/CSimpleMap.h.
|
private |
The stored data.
Definition at line 148 of file maps/CSimpleMap.h.
Page generated by Doxygen 1.9.5 for MRPT 1.4.0 SVN: at Sun Nov 27 02:56:26 UTC 2022 |