class mrpt::maps::CSimpleMap¶
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.
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
#include <mrpt/maps/CSimpleMap.h> class CSimpleMap: public mrpt::serialization::CSerializable { public: // typedefs typedef std::pair<mrpt::poses::CPose3DPDF::Ptr, mrpt::obs::CSensoryFrame::Ptr> 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; // construction CSimpleMap(); CSimpleMap(const CSimpleMap& o); // methods bool saveToFile(const std::string& filName) const; bool loadFromFile(const std::string& filName); size_t size() const; bool empty() const; void get(size_t index, mrpt::poses::CPose3DPDF::Ptr& out_posePDF, mrpt::obs::CSensoryFrame::Ptr& out_SF) const; void set(size_t index, const mrpt::poses::CPose3DPDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void set(size_t index, const mrpt::poses::CPosePDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void remove(size_t index); void insert(const mrpt::poses::CPose3DPDF* in_posePDF, const mrpt::obs::CSensoryFrame& in_SF); void insert(const mrpt::poses::CPose3DPDF* in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void insert(const mrpt::poses::CPose3DPDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void insertToPos(size_t index, const mrpt::poses::CPose3DPDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void insert(const mrpt::poses::CPosePDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void insert(const mrpt::poses::CPosePDF* in_posePDF, const mrpt::obs::CSensoryFrame& in_SF); void insert(const mrpt::poses::CPosePDF* in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void clear(); void changeCoordinatesOrigin(const mrpt::poses::CPose3D& newOrigin); 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(); CSimpleMap& operator = (const CSimpleMap& o); };
Construction¶
CSimpleMap()
Default constructor (empty map)
CSimpleMap(const CSimpleMap& o)
Copy constructor.
Methods¶
bool saveToFile(const std::string& filName) const
Save this object to a .simplemap binary file (compressed with gzip)
Returns:
false on any error.
See also:
bool loadFromFile(const std::string& filName)
Load the contents of this object from a .simplemap binary file (possibly compressed with gzip)
Returns:
false on any error.
See also:
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::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.
Parameters:
std::exception |
On index out of bounds. |
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’.
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).
Parameters:
std::exception |
On index out of bounds. |
See also:
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’.
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.
Parameters:
std::exception |
On index out of bounds. |
See also:
void remove(size_t index)
Deletes the i’th pair, first one is index ‘0’.
Parameters:
std::exception |
On index out of bounds. |
See also:
void 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 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).
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).
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.
Parameters:
index |
Position in the simplemap where new element will be inserted to |
void 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.
void 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 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.
void clear()
Remove all stored pairs.
See also:
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.
CSimpleMap& operator = (const CSimpleMap& o)
Copy.