Main MRPT website > C++ reference for MRPT 1.9.9
CMetricMapBuilderRBPF.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-2017, 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 CMetricMapBuilderRBPF_H
10 #define CMetricMapBuilderRBPF_H
11 
15 
19 
20 namespace mrpt
21 {
22 namespace slam
23 {
24 /** This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to
25  * map building (SLAM).
26  * Internally, the list of particles, each containing a hypothesis for the
27  * robot path plus its associated
28  * metric map, is stored in an object of class CMultiMetricMapPDF.
29  *
30  * This class processes robot actions and observations sequentially (through
31  * the method CMetricMapBuilderRBPF::processActionObservation)
32  * and exploits the generic design of metric map classes in MRPT to deal with
33  * any number and combination of maps simultaneously: the likelihood
34  * of observations is the product of the likelihood in the different maps,
35  * etc.
36  *
37  * A number of particle filter methods are implemented as well, by selecting
38  * the appropriate values in TConstructionOptions::PF_options.
39  * Not all the PF algorithms are implemented for all kinds of maps.
40  *
41  * For an example of usage, check the application "rbpf-slam", in
42  * "apps/RBPF-SLAM". See also the <a
43  * href="http://www.mrpt.org/Application:RBPF-SLAM" >wiki page</a>.
44  *
45  * \note Since MRPT 0.7.2, the new variables
46  * "localizeLinDistance,localizeAngDistance" are introduced to provide a way to
47  * update the robot pose at a different rate than the map is updated.
48  * \note Since MRPT 0.7.1 the semantics of the parameters
49  * "insertionLinDistance" and "insertionAngDistance" changes: the entire RBFP is
50  * now NOT updated unless odometry increments surpass the threshold (previously,
51  * only the map was NOT updated). This is done to gain efficiency.
52  * \note Since MRPT 0.6.2 this class implements full 6D SLAM. Previous versions
53  * worked in 2D + heading only.
54  *
55  * \sa CMetricMap \ingroup metric_slam_grp
56  */
58 {
59  public:
60  /** The map PDF: It includes a path and associated map for each particle. */
62 
63  protected:
64  /** The configuration of the particle filter */
66 
67  /** Distances (linear and angular) for inserting a new observation into the
68  * map. */
70 
71  /** Distances (linear and angular) for updating the robot pose estimate (and
72  * particles weighs, if applicable). */
74 
75  /** Traveled distance since last localization update */
77  /** Traveled distance since last map update */
79 
80  public:
81  /** Options for building a CMetricMapBuilderRBPF object, passed to the
82  * constructor.
83  */
85  {
86  public:
87  /** Constructor */
89  void loadFromConfigFile(
91  const std::string& section) override; // See base docs
92  void dumpToTextStream(
93  mrpt::utils::CStream& out) const override; // See base docs
94 
97 
100 
102 
105  mrpt::utils::VerbosityLevel verbosity_level;
106  };
107 
108  /** Constructor. */
109  CMetricMapBuilderRBPF(const TConstructionOptions& initializationOptions);
110 
111  /** This second constructor is created for the situation where a class
112 member needs to be
113 of type CMetricMapBuilderRBPF */
115 
116  /** Copy Operator. */
118 
119  /** Destructor. */
120  virtual ~CMetricMapBuilderRBPF();
121 
122  /** Initialize the method, starting with a known location PDF "x0"(if
123  * supplied, set to nullptr to left unmodified) and a given fixed, past map.
124  */
125  void initialize(
126  const mrpt::maps::CSimpleMap& initialMap = mrpt::maps::CSimpleMap(),
127  const mrpt::poses::CPosePDF* x0 = nullptr);
128 
129  /** Clear all elements of the maps.
130  */
131  void clear();
132 
133  /** Returns a copy of the current best pose estimation as a pose PDF.
134  */
136 
137  /** Returns the current most-likely path estimation (the path associated to
138  * the most likely particle).
139  */
141  std::deque<mrpt::math::TPose3D>& outPath) const;
142 
143  /** Appends a new action and observations to update this map: See the
144  *description of the class at the top of this page to see a more complete
145  *description.
146  * \param action The incremental 2D pose change in the robot pose. This
147  *value is deterministic.
148  * \param observations The set of observations that robot senses at the new
149  *pose.
150  * Statistics will be saved to statsLastIteration
151  */
154  mrpt::obs::CSensoryFrame& observations);
155 
156  /** Fills "out_map" with the set of "poses"-"sensory-frames", thus the so
157  * far built map.
158  */
159  void getCurrentlyBuiltMap(mrpt::maps::CSimpleMap& out_map) const;
160 
161  /** Returns the map built so far. NOTE that for efficiency a pointer to the
162  * internal object is passed, DO NOT delete nor modify the object in any
163  * way, if desired, make a copy of ir with "clone()".
164  */
166 
167  /** Returns just how many sensory-frames are stored in the currently build
168  * map.
169  */
170  unsigned int getCurrentlyBuiltMapSize();
171 
172  /** A useful method for debugging: the current map (and/or poses) estimation
173  * is dumped to an image file.
174  * \param file The output file name
175  * \param formatEMF_BMP Output format = true:EMF, false:BMP
176  */
178  const std::string& file, bool formatEMF_BMP = true);
179 
180  /** A useful method for debugging: draws the current map and path hypotheses
181  * to a CCanvas */
183 
184  /** A logging utility: saves the current path estimation for each particle
185  * in a text file (a row per particle, each 3-column-entry is a set
186  * [x,y,phi], respectively).
187  */
189 
190  double getCurrentJointEntropy();
191 
192  /** This structure will hold stats after each execution of
193  * processActionObservation
194  */
195  struct TStats
196  {
198  /** Whether the SF has been inserted in the metric maps. */
200  };
201 
202  /** This structure will hold stats after each execution of
203  * processActionObservation */
205 
206 }; // End of class def.
207 
208 } // namespace slam
209 } // namespace mrpt
210 #endif
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
unsigned int getCurrentlyBuiltMapSize()
Returns just how many sensory-frames are stored in the currently build map.
bool observationsInserted
Whether the SF has been inserted in the metric maps.
CMetricMapBuilderRBPF & operator=(const CMetricMapBuilderRBPF &src)
Copy Operator.
mrpt::poses::CPose3D odoIncrementSinceLastMapUpdate
Traveled distance since last map update.
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:35
float insertionLinDistance
Distances (linear and angular) for inserting a new observation into the map.
float localizeLinDistance
Distances (linear and angular) for updating the robot pose estimate (and particles weighs...
void saveCurrentPathEstimationToTextFile(const std::string &fil)
A logging utility: saves the current path estimation for each particle in a text file (a row per part...
void getCurrentlyBuiltMap(mrpt::maps::CSimpleMap &out_map) const
Fills "out_map" with the set of "poses"-"sensory-frames", thus the so far built map.
GLuint src
Definition: glext.h:7278
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
Declares a class for storing a collection of robot actions.
void clear()
Clear all elements of the maps.
This class allows loading and storing values and vectors of different types from a configuration text...
const mrpt::maps::CMultiMetricMap * getCurrentlyBuiltMetricMap() const
Returns the map built so far.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
void saveCurrentEstimationToImage(const std::string &file, bool formatEMF_BMP=true)
A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file...
mrpt::maps::CMultiMetricMapPDF mapPDF
The map PDF: It includes a path and associated map for each particle.
GLint GLvoid * img
Definition: glext.h:3763
mrpt::poses::CPose3DPDF::Ptr getCurrentPoseEstimation() const
Returns a copy of the current best pose estimation as a pose PDF.
CMetricMapBuilderRBPF()
This second constructor is created for the situation where a class member needs to be of type CMetric...
std::shared_ptr< CPose3DPDF > Ptr
Definition: CPose3DPDF.h:45
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:54
void initialize(const mrpt::maps::CSimpleMap &initialMap=mrpt::maps::CSimpleMap(), const mrpt::poses::CPosePDF *x0=nullptr)
Initialize the method, starting with a known location PDF "x0"(if supplied, set to nullptr to left un...
This virtual class is the base for SLAM implementations.
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:41
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
TStats m_statsLastIteration
This structure will hold stats after each execution of processActionObservation.
This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM)...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
The configuration of a particle filter.
The struct for passing extra simulation parameters to the prediction/update stage when running a part...
void getCurrentMostLikelyPath(std::deque< mrpt::math::TPose3D > &outPath) const
Returns the current most-likely path estimation (the path associated to the most likely particle)...
mrpt::maps::CMultiMetricMapPDF::TPredictionParams predictionOptions
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
This virtual class defines the interface of any object accepting drawing primitives on it...
Definition: CCanvas.h:43
mrpt::poses::CPose3DPDFGaussian odoIncrementSinceLastLocalization
Traveled distance since last localization update.
void processActionObservation(mrpt::obs::CActionCollection &action, mrpt::obs::CSensoryFrame &observations)
Appends a new action and observations to update this map: See the description of the class at the top...
mrpt::maps::TSetOfMetricMapInitializers mapsInitializers
This structure will hold stats after each execution of processActionObservation.
bayes::CParticleFilter::TParticleFilterOptions PF_options
void drawCurrentEstimationToImage(utils::CCanvas *img)
A useful method for debugging: draws the current map and path hypotheses to a CCanvas.
This class stores any customizable set of metric maps.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...
Options for building a CMetricMapBuilderRBPF object, passed to the constructor.
bayes::CParticleFilter::TParticleFilterOptions m_PF_options
The configuration of the particle filter.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019