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-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 CMetricMapBuilderRBPF_H
10 #define CMetricMapBuilderRBPF_H
11 
15 
20 
21 namespace mrpt::slam
22 {
23 /** This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to
24  * map building (SLAM).
25  * Internally, the list of particles, each containing a hypothesis for the
26  * robot path plus its associated
27  * metric map, is stored in an object of class CMultiMetricMapPDF.
28  *
29  * This class processes robot actions and observations sequentially (through
30  * the method CMetricMapBuilderRBPF::processActionObservation)
31  * and exploits the generic design of metric map classes in MRPT to deal with
32  * any number and combination of maps simultaneously: the likelihood
33  * of observations is the product of the likelihood in the different maps,
34  * etc.
35  *
36  * A number of particle filter methods are implemented as well, by selecting
37  * the appropriate values in TConstructionOptions::PF_options.
38  * Not all the PF algorithms are implemented for all kinds of maps.
39  *
40  * For an example of usage, check the application "rbpf-slam", in
41  * "apps/RBPF-SLAM". See also the <a
42  * href="http://www.mrpt.org/Application:RBPF-SLAM" >wiki page</a>.
43  *
44  * \note Since MRPT 0.7.2, the new variables
45  * "localizeLinDistance,localizeAngDistance" are introduced to provide a way to
46  * update the robot pose at a different rate than the map is updated.
47  * \note Since MRPT 0.7.1 the semantics of the parameters
48  * "insertionLinDistance" and "insertionAngDistance" changes: the entire RBFP is
49  * now NOT updated unless odometry increments surpass the threshold (previously,
50  * only the map was NOT updated). This is done to gain efficiency.
51  * \note Since MRPT 0.6.2 this class implements full 6D SLAM. Previous versions
52  * worked in 2D + heading only.
53  *
54  * \sa CMetricMap \ingroup metric_slam_grp
55  */
57 {
58  public:
59  /** The map PDF: It includes a path and associated map for each particle. */
61 
62  protected:
63  /** The configuration of the particle filter */
65 
66  /** Distances (linear and angular) for inserting a new observation into the
67  * map. */
69 
70  /** Distances (linear and angular) for updating the robot pose estimate (and
71  * particles weighs, if applicable). */
73 
74  /** Traveled distance since last localization update */
76  /** Traveled distance since last map update */
78 
79  public:
80  /** Options for building a CMetricMapBuilderRBPF object, passed to the
81  * constructor.
82  */
84  {
85  public:
86  /** Constructor */
88  void loadFromConfigFile(
90  const std::string& section) override; // See base docs
91  void dumpToTextStream(
92  std::ostream& out) const override; // See base docs
93 
96 
99 
101 
105  };
106 
107  /** Constructor. */
108  CMetricMapBuilderRBPF(const TConstructionOptions& initializationOptions);
109 
110  /** This second constructor is created for the situation where a class
111 member needs to be
112 of type CMetricMapBuilderRBPF */
114 
115  /** Copy Operator. */
117 
118  /** Destructor. */
119  virtual ~CMetricMapBuilderRBPF();
120 
121  /** Initialize the method, starting with a known location PDF "x0"(if
122  * supplied, set to nullptr to left unmodified) and a given fixed, past map.
123  */
124  void initialize(
125  const mrpt::maps::CSimpleMap& initialMap = mrpt::maps::CSimpleMap(),
126  const mrpt::poses::CPosePDF* x0 = nullptr);
127 
128  /** Clear all elements of the maps.
129  */
130  void clear();
131 
132  /** Returns a copy of the current best pose estimation as a pose PDF.
133  */
135 
136  /** Returns the current most-likely path estimation (the path associated to
137  * the most likely particle).
138  */
140  std::deque<mrpt::math::TPose3D>& outPath) const;
141 
142  /** Appends a new action and observations to update this map: See the
143  *description of the class at the top of this page to see a more complete
144  *description.
145  * \param action The incremental 2D pose change in the robot pose. This
146  *value is deterministic.
147  * \param observations The set of observations that robot senses at the new
148  *pose.
149  * Statistics will be saved to statsLastIteration
150  */
153  mrpt::obs::CSensoryFrame& observations);
154 
155  /** Fills "out_map" with the set of "poses"-"sensory-frames", thus the so
156  * far built map.
157  */
158  void getCurrentlyBuiltMap(mrpt::maps::CSimpleMap& out_map) const;
159 
160  /** Returns the map built so far. NOTE that for efficiency a pointer to the
161  * internal object is passed, DO NOT delete nor modify the object in any
162  * way, if desired, make a copy of ir with "clone()".
163  */
165 
166  /** Returns just how many sensory-frames are stored in the currently build
167  * map.
168  */
169  unsigned int getCurrentlyBuiltMapSize();
170 
171  /** A useful method for debugging: the current map (and/or poses) estimation
172  * is dumped to an image file.
173  * \param file The output file name
174  * \param formatEMF_BMP Output format = true:EMF, false:BMP
175  */
177  const std::string& file, bool formatEMF_BMP = true);
178 
179  /** A useful method for debugging: draws the current map and path hypotheses
180  * to a CCanvas */
182 
183  /** A logging utility: saves the current path estimation for each particle
184  * in a text file (a row per particle, each 3-column-entry is a set
185  * [x,y,phi], respectively).
186  */
188 
189  double getCurrentJointEntropy();
190 
191  /** This structure will hold stats after each execution of
192  * processActionObservation
193  */
194  struct TStats
195  {
197  /** Whether the SF has been inserted in the metric maps. */
199  };
200 
201  /** This structure will hold stats after each execution of
202  * processActionObservation */
204 
205 }; // End of class def.
206 
207 }
208 #endif
209 
210 
unsigned int getCurrentlyBuiltMapSize()
Returns just how many sensory-frames are stored in the currently build map.
This virtual class defines the interface of any object accepting drawing primitives on it...
Definition: CCanvas.h:40
VerbosityLevel
Enumeration of available verbosity levels.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
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:33
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.
const mrpt::maps::CMultiMetricMap * getCurrentlyBuiltMetricMap() const
Returns the map built so far.
This class allows loading and storing values and vectors of different types from a configuration text...
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...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:52
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:39
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
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:86
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 ...
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
This class stores any customizable set of metric maps.
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.
void drawCurrentEstimationToImage(mrpt::img::CCanvas *img)
A useful method for debugging: draws the current map and path hypotheses to a CCanvas.



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