Main MRPT website > C++ reference for MRPT 1.4.0
maps/CSimpleMap.h
Go to the documentation of this file.
1/* +---------------------------------------------------------------------------+
2 | Mobile Robot Programming Toolkit (MRPT) |
3 | http://www.mrpt.org/ |
4 | |
5 | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6 | See: http://www.mrpt.org/Authors - All rights reserved. |
7 | Released under BSD License. See details in http://www.mrpt.org/License |
8 +---------------------------------------------------------------------------+ */
9#ifndef CSimpleMap_H
10#define CSimpleMap_H
11
14#include <mrpt/poses/CPosePDF.h>
16#include <mrpt/obs/obs_frwds.h>
17
18namespace mrpt
19{
20namespace maps
21{
22 // This must be added to any CSerializable derived class:
24
25 /** This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be totally determined with this information.
26 * The pose of the sensory frame is not deterministic, but described by some PDF. Full 6D poses are used.
27 *
28 * \note Objects of this class are serialized into (possibly GZ-compressed) files with the extension ".simplemap".
29 *
30 * \note 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.
31 * \sa CSensoryFrame, CPosePDF
32 * \ingroup mrpt_obs_grp
33 */
34 class OBS_IMPEXP CSimpleMap : public mrpt::utils::CSerializable
35 {
36 // This must be added to any CSerializable derived class:
38 public:
39 CSimpleMap(); //!< Default constructor (empty map)
40 CSimpleMap( const CSimpleMap &o ); //!< Copy constructor
41 virtual ~CSimpleMap(); //!< Destructor:
42 CSimpleMap & operator = ( const CSimpleMap& o); //!< Copy
43
44 /** \name Map access and modification
45 * @{ */
46
47 /** Save this object to a .simplemap binary file (compressed with gzip)
48 * \sa loadFromFile
49 * \return false on any error. */
50 bool saveToFile(const std::string &filName) const;
51
52 /** Load the contents of this object from a .simplemap binary file (possibly compressed with gzip)
53 * \sa saveToFile
54 * \return false on any error. */
55 bool loadFromFile(const std::string &filName);
56
57 size_t size() const; //!< Returns the count of pairs (pose,sensory data)
58 bool empty() const; //!< Returns size()!=0
59
60 /** Access to the i'th pair, first one is index '0'. NOTE: This method
61 * returns pointers to the objects inside the list, nor a copy of them,
62 * so <b>do neither modify them nor delete them</b>.
63 * NOTE: You can pass a NULL pointer if you dont need one of the two variables to be returned.
64 * \exception std::exception On index out of bounds.
65 */
66 void get(size_t index, mrpt::poses::CPose3DPDFPtr &out_posePDF, mrpt::obs::CSensoryFramePtr &out_SF ) const ;
67
68 /** Changes the i'th pair, first one is index '0'.
69 * The referenced object is COPIED, so you can freely destroy the object passed as parameter after calling this.
70 * 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).
71 * \exception std::exception On index out of bounds.
72 * \sa insert, get, remove
73 */
74 void set(size_t index, const mrpt::poses::CPose3DPDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF );
75
76 /** Changes the i'th pair, first one is index '0'.
77 * The referenced object is COPIED, so you can freely destroy the object passed as parameter after calling this.
78 * 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).
79 * This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.
80 * \exception std::exception On index out of bounds.
81 * \sa insert, get, remove
82 */
83 void set(size_t index, const mrpt::poses::CPosePDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF );
84
85 /** Deletes the i'th pair, first one is index '0'.
86 * \exception std::exception On index out of bounds.
87 * \sa insert, get, set
88 */
89 void remove(size_t index);
90
91 /** Add a new pair to the sequence. The objects are copied, so original ones can be free if desired after insertion. */
92 void insert( const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF );
93
94 /** Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique). */
95 void insert( const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF );
96
97 /** Add a new pair to the sequence, making a copy of the smart pointer (it's not made unique). */
98 void insert( const mrpt::poses::CPose3DPDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF );
99
100 /** Add a new pair to the sequence. The objects are copied, so original ones can be free if desired
101 * after insertion.
102 * This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.
103 */
104 void insert( const mrpt::poses::CPosePDFPtr &in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF );
105
106 /** Add a new pair to the sequence. The objects are copied, so original ones can be free if desired
107 * after insertion.
108 * This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.
109 */
110 void insert( const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF );
111
112 /** Add a new pair to the sequence. The objects are copied, so original ones can be free if desired
113 * after insertion.
114 * This version for 2D PDFs just converts the 2D PDF into 3D before calling the 3D version.
115 */
116 void insert( const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFramePtr &in_SF );
117
118 void clear(); //!< Remove all stored pairs. \sa remove
119
120 /** Change the coordinate origin of all stored poses, for consistency with future new poses to enter in the system. */
122
123 /** @} */
124
125 /** \name Iterators API
126 * @{ */
127 typedef std::pair<mrpt::poses::CPose3DPDFPtr,mrpt::obs::CSensoryFramePtr> TPosePDFSensFramePair;
128 typedef std::deque<TPosePDFSensFramePair> TPosePDFSensFramePairList;
129
130 typedef TPosePDFSensFramePairList::const_iterator const_iterator;
131 typedef TPosePDFSensFramePairList::iterator iterator;
132 typedef TPosePDFSensFramePairList::reverse_iterator reverse_iterator;
133 typedef TPosePDFSensFramePairList::const_reverse_iterator const_reverse_iterator;
134
135 inline const_iterator begin() const { return m_posesObsPairs.begin(); }
136 inline const_iterator end() const { return m_posesObsPairs.end(); }
137 inline iterator begin() { return m_posesObsPairs.begin(); }
138 inline iterator end() { return m_posesObsPairs.end(); }
139
140 inline const_reverse_iterator rbegin() const { return m_posesObsPairs.rbegin(); }
141 inline const_reverse_iterator rend() const { return m_posesObsPairs.rend(); }
142 inline reverse_iterator rbegin() { return m_posesObsPairs.rbegin(); }
143 inline reverse_iterator rend() { return m_posesObsPairs.rend(); }
144 /** @} */
145
146 private:
147 /** The stored data */
149
150 }; // End of class def.
152
153 } // End of namespace
154} // End of namespace
155#endif
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
CSimpleMap()
Default constructor (empty map)
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'.
reverse_iterator rend()
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).
bool empty() const
Returns size()!=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 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).
std::deque< TPosePDFSensFramePair > TPosePDFSensFramePairList
TPosePDFSensFramePairList::const_reverse_iterator const_reverse_iterator
const_reverse_iterator rend() const
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.
reverse_iterator rbegin()
std::pair< mrpt::poses::CPose3DPDFPtr, mrpt::obs::CSensoryFramePtr > TPosePDFSensFramePair
CSimpleMap(const CSimpleMap &o)
Copy constructor.
TPosePDFSensFramePairList m_posesObsPairs
The stored data.
bool saveToFile(const std::string &filName) const
Save this object to a .simplemap binary file (compressed with gzip)
const_iterator end() const
virtual ~CSimpleMap()
Destructor:
size_t size() const
Returns the count of pairs (pose,sensory data)
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::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
Add a new pair to the sequence.
TPosePDFSensFramePairList::iterator iterator
bool loadFromFile(const std::string &filName)
Load the contents of this object from a .simplemap binary file (possibly compressed with gzip)
TPosePDFSensFramePairList::const_iterator const_iterator
TPosePDFSensFramePairList::reverse_iterator reverse_iterator
void insert(const mrpt::poses::CPosePDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
Add a new pair to the sequence.
const_reverse_iterator rbegin() const
void remove(size_t index)
Deletes the i'th pair, first one is index '0'.
void changeCoordinatesOrigin(const mrpt::poses::CPose3D &newOrigin)
Change the coordinate origin of all stored poses, for consistency with future new poses to enter in t...
const_iterator begin() const
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'.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:73
Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually).
Definition: CPose3DPDF.h:41
Declares a class that represents a probability density function (pdf) of a 2D pose (x,...
Definition: CPosePDF.h:40
struct OBS_IMPEXP CSensoryFramePtr
struct BASE_IMPEXP CPose3DPDFPtr
Definition: CPose3DPDF.h:23
struct BASE_IMPEXP CPosePDFPtr
Definition: CPosePDF.h:25
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.



Page generated by Doxygen 1.9.5 for MRPT 1.4.0 SVN: at Sun Nov 27 02:47:40 UTC 2022