class mrpt::maps::CSimpleMap
A view-based representation of a metric map.
This comprises a list of <ProbabilisticPose,SensoryFrame>
pairs, that is, the poses (keyframes) from which a set of observations where gathered:
Poses, in the global
map
frame of reference, are stored as probabilistic PDFs over SE(3) as instances of mrpt::poses::CPose3DPDFObservations are stored as mrpt::obs::CSensoryFrame.
Note that in order to generate an actual metric map (occupancy grid, point cloud, octomap, etc.) from a “simple map”, you must instantiate the desired metric map class and invoke its virtual method mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations().
Objects of this class are serialized into GZ-compressed files with the extension .simplemap
. See Robotics file formats.
See also:
mrpt::obs::CSensoryFrame, mrpt::poses::CPose3DPDF, mrpt::maps::CMetricMap
#include <mrpt/maps/CSimpleMap.h> class CSimpleMap: public mrpt::serialization::CSerializable { public: // typedefs typedef std::deque<Pair> 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; // structs struct ConstPair; struct Pair; // construction CSimpleMap(); CSimpleMap(const CSimpleMap& o); // methods const_iterator begin() const; const_iterator end() const; const_iterator cbegin() const; const_iterator cend() const; iterator begin(); iterator end(); const_reverse_iterator rbegin() const; const_reverse_iterator rend() const; const_reverse_iterator crbegin() const; const_reverse_iterator crend() const; reverse_iterator rbegin(); reverse_iterator rend(); 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::ConstPtr& out_posePDF, mrpt::obs::CSensoryFrame::ConstPtr& out_SF) const; std::tuple<mrpt::poses::CPose3DPDF::ConstPtr, mrpt::obs::CSensoryFrame::ConstPtr> get(size_t index) const; ConstPair getAsPair(size_t index) const; Pair& getAsPair(size_t index); void get(size_t index, mrpt::poses::CPose3DPDF::Ptr& out_posePDF, mrpt::obs::CSensoryFrame::Ptr& out_SF); std::tuple<mrpt::poses::CPose3DPDF::Ptr, mrpt::obs::CSensoryFrame::Ptr> get(size_t index); 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 Pair& poseSF); 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::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void insert(const Pair& poseSF); void insert(const mrpt::poses::CPosePDF& in_posePDF, const mrpt::obs::CSensoryFrame& in_SF); void insert(const mrpt::poses::CPosePDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF); void clear(); void changeCoordinatesOrigin(const mrpt::poses::CPose3D& newOrigin); CSimpleMap& operator = (const CSimpleMap& o); };
Construction
CSimpleMap()
Default ctor: empty map.
CSimpleMap(const CSimpleMap& o)
Copy constructor, makes a deep copy of all data.
Methods
bool saveToFile(const std::string& filName) const
Save this object to a .simplemap binary file (compressed with gzip) See Robotics file formats.
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) See Robotics file formats.
Returns:
false on any error.
See also:
size_t size() const
Returns the count of (pose,sensoryFrame) pairs.
bool empty() const
Returns size()!=0.
void get(size_t index, mrpt::poses::CPose3DPDF::ConstPtr& out_posePDF, mrpt::obs::CSensoryFrame::ConstPtr& out_SF) const
Access to the 0-based index i’th pair.
Parameters:
std::exception |
On index out of bounds. |
std::tuple<mrpt::poses::CPose3DPDF::ConstPtr, mrpt::obs::CSensoryFrame::ConstPtr> get(size_t index) const
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
void get(size_t index, mrpt::poses::CPose3DPDF::Ptr& out_posePDF, mrpt::obs::CSensoryFrame::Ptr& out_SF)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
std::tuple<mrpt::poses::CPose3DPDF::Ptr, mrpt::obs::CSensoryFrame::Ptr> get(size_t index)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
void set(size_t index, const mrpt::poses::CPose3DPDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF)
Changes the 0-based index i’th pair.
If one of either in_posePDF
or in_SF
are empty shared_ptr
s, the corresponding field in the map is not modified.
Parameters:
std::exception |
On index out of bounds. |
See also:
void set(size_t index, const Pair& poseSF)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
void remove(size_t index)
Deletes the 0-based index i’th pair.
Parameters:
std::exception |
On index out of bounds. |
See also:
void insert(const mrpt::poses::CPose3DPDF& in_posePDF, const mrpt::obs::CSensoryFrame& in_SF)
Adds a new keyframe (SE(3) pose) to the view-based map, making a deep copy of the pose PDF (observations within the SF are always copied as shared_ptr
s).
void insert(const mrpt::poses::CPose3DPDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF)
Adds a new keyframe (SE(3) pose) to the view-based map.
Both shared pointers are copied (shallow object copies).
void insert(const Pair& poseSF)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
void insert(const mrpt::poses::CPosePDF& in_posePDF, const mrpt::obs::CSensoryFrame& in_SF)
Adds a new keyframe (SE(2) pose) to the view-based map, making a deep copy of the pose PDF (observations within the SF are always copied as shared_ptr
s).
void insert(const mrpt::poses::CPosePDF::Ptr& in_posePDF, const mrpt::obs::CSensoryFrame::Ptr& in_SF)
Adds a new keyframe (SE(2) pose) to the view-based map.
Both shared pointers are copied (shallow object copies).
void clear()
Remove all stored pairs.
See also:
void changeCoordinatesOrigin(const mrpt::poses::CPose3D& newOrigin)
Change the coordinate origin of all stored poses, that is, translates and rotates the map such that the old SE(3) origin (identity transformation) becomes the new provided one.
CSimpleMap& operator = (const CSimpleMap& o)
Copy, making a deep copy of all data.