MRPT  1.9.9
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-2018, 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 
13 #include <mrpt/obs/CSensoryFrame.h>
14 #include <mrpt/poses/CPosePDF.h>
15 #include <mrpt/poses/CPose3DPDF.h>
16 #include <mrpt/obs/obs_frwds.h>
17 
18 namespace mrpt::maps
19 {
20 /** This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs,
21  * thus a "metric map" can be totally determined with this information.
22  * The pose of the sensory frame is not deterministic, but described by some
23  * PDF. Full 6D poses are used.
24  *
25  * \note Objects of this class are serialized into (possibly GZ-compressed)
26  * files with the extension ".simplemap".
27  *
28  * \note Before MRPT 0.9.0 the name of this class was "CSensFrameProbSequence",
29  * that's why there is a type with that name to allow backward compatibility.
30  * \sa CSensoryFrame, CPosePDF
31  * \ingroup mrpt_obs_grp
32  */
34 {
36  public:
37  /** Default constructor (empty map) */
38  CSimpleMap() = default;
39  /** Copy constructor */
40  CSimpleMap(const CSimpleMap& o);
41  /** Copy */
42  CSimpleMap& operator=(const CSimpleMap& o);
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
53  * compressed with gzip)
54  * \sa saveToFile
55  * \return false on any error. */
56  bool loadFromFile(const std::string& filName);
57 
58  /** Returns the count of pairs (pose,sensory data) */
59  size_t size() const;
60  /** Returns size()!=0 */
61  bool empty() const;
62 
63  /** Access to the i'th pair, first one is index '0'. NOTE: This method
64  * returns pointers to the objects inside the list, nor a copy of them,
65  * so <b>do neither modify them nor delete them</b>.
66  * NOTE: You can pass a nullptr pointer if you dont need one of the two
67  * variables to be returned.
68  * \exception std::exception On index out of bounds.
69  */
70  void get(
71  size_t index, mrpt::poses::CPose3DPDF::Ptr& out_posePDF,
72  mrpt::obs::CSensoryFrame::Ptr& out_SF) const;
73 
74  /** Changes the i'th pair, first one is index '0'.
75  * The referenced object is COPIED, so you can freely destroy the object
76  * passed as parameter after calling this.
77  * If one of the pointers is nullptr, the corresponding contents of the
78  * current i'th pair is not modified (i.e. if you want just to modify one of
79  * the values).
80  * \exception std::exception On index out of bounds.
81  * \sa insert, get, remove
82  */
83  void set(
84  size_t index, const mrpt::poses::CPose3DPDF::Ptr& in_posePDF,
85  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
86 
87  /** Changes the i'th pair, first one is index '0'.
88  * The referenced object is COPIED, so you can freely destroy the object
89  * passed as parameter after calling this.
90  * If one of the pointers is nullptr, the corresponding contents of the
91  * current i'th pair is not modified (i.e. if you want just to modify one of
92  * the values).
93  * This version for 2D PDFs just converts the 2D PDF into 3D before calling
94  * the 3D version.
95  * \exception std::exception On index out of bounds.
96  * \sa insert, get, remove
97  */
98  void set(
99  size_t index, const mrpt::poses::CPosePDF::Ptr& in_posePDF,
100  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
101 
102  /** Deletes the i'th pair, first one is index '0'.
103  * \exception std::exception On index out of bounds.
104  * \sa insert, get, set
105  */
106  void remove(size_t index);
107 
108  /** Add a new pair to the sequence. The objects are copied, so original ones
109  * can be free if desired after insertion. */
110  void insert(
111  const mrpt::poses::CPose3DPDF* in_posePDF,
112  const mrpt::obs::CSensoryFrame& in_SF);
113 
114  /** Add a new pair to the sequence, making a copy of the smart pointer (it's
115  * not made unique). */
116  void insert(
117  const mrpt::poses::CPose3DPDF* in_posePDF,
118  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
119 
120  /** Add a new pair to the sequence, making a copy of the smart pointer (it's
121  * not made unique). */
122  void insert(
123  const mrpt::poses::CPose3DPDF::Ptr& in_posePDF,
124  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
125 
126  /** Insert a new pair to the sequence, making a copy of the smart pointer
127  (it's
128  * not made unique) to
129  \param index Position in the simplemap where new element will be inserted to
130  */
131  void insertToPos(
132  size_t index, const mrpt::poses::CPose3DPDF::Ptr& in_posePDF,
133  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
134 
135  /** Add a new pair to the sequence. The objects are copied, so original ones
136  * can be free if desired
137  * after insertion.
138  * This version for 2D PDFs just converts the 2D PDF into 3D before calling
139  * the 3D version.
140  */
141  void insert(
142  const mrpt::poses::CPosePDF::Ptr& in_posePDF,
143  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
144 
145  /** Add a new pair to the sequence. The objects are copied, so original ones
146  * can be free if desired
147  * after insertion.
148  * This version for 2D PDFs just converts the 2D PDF into 3D before calling
149  * the 3D version.
150  */
151  void insert(
152  const mrpt::poses::CPosePDF* in_posePDF,
153  const mrpt::obs::CSensoryFrame& in_SF);
154 
155  /** Add a new pair to the sequence. The objects are copied, so original ones
156  * can be free if desired
157  * after insertion.
158  * This version for 2D PDFs just converts the 2D PDF into 3D before calling
159  * the 3D version.
160  */
161  void insert(
162  const mrpt::poses::CPosePDF* in_posePDF,
163  const mrpt::obs::CSensoryFrame::Ptr& in_SF);
164 
165  /** Remove all stored pairs. \sa remove */
166  void clear();
167 
168  /** Change the coordinate origin of all stored poses, for consistency with
169  * future new poses to enter in the system. */
170  void changeCoordinatesOrigin(const mrpt::poses::CPose3D& newOrigin);
171 
172  /** @} */
173 
174  /** \name Iterators API
175  * @{ */
176  using TPosePDFSensFramePair =
177  std::pair<mrpt::poses::CPose3DPDF::Ptr, mrpt::obs::CSensoryFrame::Ptr>;
178  using TPosePDFSensFramePairList = std::deque<TPosePDFSensFramePair>;
179 
182  using reverse_iterator = TPosePDFSensFramePairList::reverse_iterator;
183  using const_reverse_iterator =
184  TPosePDFSensFramePairList::const_reverse_iterator;
185 
186  inline const_iterator begin() const { return m_posesObsPairs.begin(); }
187  inline const_iterator end() const { return m_posesObsPairs.end(); }
188  inline iterator begin() { return m_posesObsPairs.begin(); }
189  inline iterator end() { return m_posesObsPairs.end(); }
191  {
192  return m_posesObsPairs.rbegin();
193  }
195  {
196  return m_posesObsPairs.rend();
197  }
198  inline reverse_iterator rbegin() { return m_posesObsPairs.rbegin(); }
199  inline reverse_iterator rend() { return m_posesObsPairs.rend(); }
200  /** @} */
201 
202  private:
203  /** The stored data */
205 
206 }; // End of class def.
207 
208 }
209 #endif
210 
211 
Scalar * iterator
Definition: eigen_plugins.h:26
std::pair< mrpt::poses::CPose3DPDF::Ptr, mrpt::obs::CSensoryFrame::Ptr > TPosePDFSensFramePair
Definition: CSimpleMap.h:177
bool empty() const
Returns size()!=0.
Definition: CSimpleMap.cpp:54
const_reverse_iterator rend() const
Definition: CSimpleMap.h:194
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:33
const_reverse_iterator rbegin() const
Definition: CSimpleMap.h:190
TPosePDFSensFramePairList::iterator iterator
Definition: CSimpleMap.h:181
CSimpleMap & operator=(const CSimpleMap &o)
Copy.
Definition: CSimpleMap.cpp:40
bool loadFromFile(const std::string &filName)
Load the contents of this object from a .simplemap binary file (possibly compressed with gzip) ...
Definition: CSimpleMap.cpp:290
TPosePDFSensFramePairList::reverse_iterator reverse_iterator
Definition: CSimpleMap.h:182
const_iterator begin() const
Definition: CSimpleMap.h:186
GLuint index
Definition: glext.h:4054
const_iterator end() const
Definition: CSimpleMap.h:187
TPosePDFSensFramePairList::const_iterator const_iterator
Definition: CSimpleMap.h:180
TPosePDFSensFramePairList::const_reverse_iterator const_reverse_iterator
Definition: CSimpleMap.h:184
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:52
size_t size() const
Returns the count of pairs (pose,sensory data)
Definition: CSimpleMap.cpp:53
GLsizei const GLchar ** string
Definition: glext.h:4101
Declares a class that represents a probability density function (pdf) of a 2D pose (x...
Definition: CPosePDF.h:39
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
std::deque< TPosePDFSensFramePair > TPosePDFSensFramePairList
Definition: CSimpleMap.h:178
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:86
reverse_iterator rbegin()
Definition: CSimpleMap.h:198
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&#39;s not made unique) to...
Definition: CSimpleMap.cpp:195
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:30
CSimpleMap()=default
Default constructor (empty map)
void insert(const mrpt::poses::CPose3DPDF *in_posePDF, const mrpt::obs::CSensoryFrame &in_SF)
Add a new pair to the sequence.
Definition: CSimpleMap.cpp:136
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...
Definition: CSimpleMap.cpp:260
const Scalar * const_iterator
Definition: eigen_plugins.h:27
TPosePDFSensFramePairList m_posesObsPairs
The stored data.
Definition: CSimpleMap.h:204
Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually)...
Definition: CPose3DPDF.h:40
reverse_iterator rend()
Definition: CSimpleMap.h:199
bool saveToFile(const std::string &filName) const
Save this object to a .simplemap binary file (compressed with gzip)
Definition: CSimpleMap.cpp:271
void clear()
Remove all stored pairs.
Definition: CSimpleMap.cpp:55



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020