Main MRPT website > C++ reference
MRPT logo
CMultiMetricMapPDF.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-2014, 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 CMultiMetricMapPDF_H
10 #define CMultiMetricMapPDF_H
11 
13 #include <mrpt/slam/CSimpleMap.h>
16 
18 
21 #include <mrpt/slam/CICP.h>
22 
24 
25 #include <mrpt/slam/link_pragmas.h>
26 
27 namespace mrpt
28 {
29 namespace slam
30 {
32 
33  /** Auxiliary class used in mrpt::slam::CMultiMetricMapPDF
34  * \ingroup mrpt_slam_grp
35  */
37  {
38  // This must be added to any CSerializable derived class:
40  public:
41  CRBPFParticleData( const TSetOfMetricMapInitializers *mapsInitializers = NULL ) :
42  mapTillNow( mapsInitializers ),
43  robotPath()
44  {
45  }
46 
48  std::deque<TPose3D> robotPath;
49  };
51 
52 
54 
55  /** Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (This class is the base of RBPF-SLAM applications).
56  * This class is used internally by the map building algorithm in "mrpt::slam::CMetricMapBuilderRBPF"
57  *
58  * \sa mrpt::slam::CMetricMapBuilderRBPF
59  * \ingroup metric_slam_grp
60  */
61  class SLAM_IMPEXP CMultiMetricMapPDF :
62  public mrpt::utils::CSerializable,
64  public mrpt::bayes::CParticleFilterDataImpl<CMultiMetricMapPDF,mrpt::bayes::CParticleFilterData<CRBPFParticleData>::CParticleList>,
65  public mrpt::slam::PF_implementation<CRBPFParticleData,CMultiMetricMapPDF>
66  {
67  friend class CMetricMapBuilderRBPF;
68  //template <class PARTICLE_TYPE, class MYSELF> friend class PF_implementation;
69 
70  // This must be added to any CSerializable derived class:
71  DEFINE_SERIALIZABLE( CMultiMetricMapPDF )
72 
73  protected:
74  /** The PF algorithm implementation.
75  */
76  void prediction_and_update_pfStandardProposal(
77  const mrpt::slam::CActionCollection * action,
78  const mrpt::slam::CSensoryFrame * observation,
79  const bayes::CParticleFilter::TParticleFilterOptions &PF_options );
80 
81  /** The PF algorithm implementation.
82  */
83  void prediction_and_update_pfOptimalProposal(
84  const mrpt::slam::CActionCollection * action,
85  const mrpt::slam::CSensoryFrame * observation,
86  const bayes::CParticleFilter::TParticleFilterOptions &PF_options );
87 
88  /** The PF algorithm implementation.
89  */
90  void prediction_and_update_pfAuxiliaryPFOptimal(
91  const mrpt::slam::CActionCollection * action,
92  const mrpt::slam::CSensoryFrame * observation,
93  const bayes::CParticleFilter::TParticleFilterOptions &PF_options );
94 
95 
96  private:
97  /** Internal buffer for the averaged map.
98  */
99  CMultiMetricMap averageMap;
100  bool averageMapIsUpdated;
101 
102  /** The SFs and their corresponding pose estimations:
103  */
105 
106  /** A mapping between indexes in the SFs to indexes in the robot paths from particles.
107  */
108  std::vector<uint32_t> SF2robotPath;
109 
110 
111  /** Entropy aux. function
112  */
113  float H(float p);
114 
115  public:
116 
117  /** The struct for passing extra simulation parameters to the prediction/update stage
118  * when running a particle filter.
119  * \sa prediction_and_update
120  */
122  {
123  /** Default settings method.
124  */
126 
127  /** See utils::CLoadableOptions
128  */
129  void loadFromConfigFile(
130  const mrpt::utils::CConfigFileBase &source,
131  const std::string &section);
132 
133  /** See utils::CLoadableOptions
134  */
135  void dumpToTextStream(CStream &out) const;
136 
137  /** [pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal")
138  * Select the map on which to calculate the optimal
139  * proposal distribution. Values:
140  * 0: Gridmap -> Uses Scan matching-based approximation (based on Stachniss' work)
141  * 1: Landmarks -> Uses matching to approximate optimal
142  * 2: Beacons -> Used for exact optimal proposal in RO-SLAM
143  * 3: Pointsmap -> Uses Scan matching-based approximation with a map of points (based on Stachniss' work)
144  * Default = 0
145  */
147 
148 
149  /** [prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum quality ratio [0,1] of the alignment such as it will be accepted. Otherwise, raw odometry is used for those bad cases (default=0.7).
150  */
152 
153  /** [update stage] If the likelihood is computed through the occupancy grid map, then this structure is passed to the map when updating the particles weights in the update stage.
154  */
156 
158 
159  CICP::TConfigParams icp_params; //!< ICP parameters, used only when "PF_algorithm=2" in the particle filter.
160 
161  } options;
162 
163  /** Constructor
164  */
165  CMultiMetricMapPDF(
167  const mrpt::slam::TSetOfMetricMapInitializers *mapsInitializers = NULL,
168  const TPredictionParams *predictionOptions = NULL );
169 
170  /** Destructor
171  */
172  virtual ~CMultiMetricMapPDF();
173 
174  /** Clear all elements of the maps, and restore all paths to a single starting pose */
175  void clear( const CPose2D &initialPose );
176 
177  /** Clear all elements of the maps, and restore all paths to a single starting pose */
178  void clear( const CPose3D &initialPose );
179 
180  /** Returns the estimate of the robot pose as a particles PDF for the instant of time "timeStep", from 0 to N-1.
181  * \sa getEstimatedPosePDF
182  */
183  void getEstimatedPosePDFAtTime(
184  size_t timeStep,
185  CPose3DPDFParticles &out_estimation ) const;
186 
187  /** Returns the current estimate of the robot pose, as a particles PDF.
188  * \sa getEstimatedPosePDFAtTime
189  */
190  void getEstimatedPosePDF( CPose3DPDFParticles &out_estimation ) const;
191 
192  /** Returns the weighted averaged map based on the current best estimation. If you need a persistent copy of this object, please use "CSerializable::duplicate" and use the copy.
193  */
194  CMultiMetricMap * getCurrentMetricMapEstimation( );
195 
196  /** Returns a pointer to the current most likely map (associated to the most likely particle).
197  */
198  CMultiMetricMap * getCurrentMostLikelyMetricMap( );
199 
200  /** Get the number of CSensoryFrame inserted into the internal member SFs */
201  size_t getNumberOfObservationsInSimplemap() const { return SFs.size(); }
202 
203  /** Insert an observation to the map, at each particle's pose and to each particle's metric map.
204  * \param sf The SF to be inserted
205  */
206  void insertObservation(CSensoryFrame &sf);
207 
208  /** Return the path (in absolute coordinate poses) for the i'th particle.
209  * \exception On index out of bounds
210  */
211  void getPath(size_t i, std::deque<math::TPose3D> &out_path) const;
212 
213  /** Returns the current entropy of paths, computed as the average entropy of poses along the path, where entropy of each pose estimation is computed as the entropy of the gaussian approximation covariance.
214  */
215  double getCurrentEntropyOfPaths();
216 
217  /** Returns the joint entropy estimation over paths and maps, acording to "Information Gain-based Exploration Using" by C. Stachniss, G. Grissetti and W.Burgard.
218  */
219  double getCurrentJointEntropy();
220 
221  /** Update the poses estimation of the member "SFs" according to the current path belief.
222  */
223  void updateSensoryFrameSequence();
224 
225  /** A logging utility: saves the current path estimation for each particle in a text file (a row per particle, each 3-column-entry is a set [x,y,phi], respectively).
226  */
227  void saveCurrentPathEstimationToTextFile( const std::string &fil );
228 
229  /** An index [0,1] measuring how much information an observation aports to the map (Typ. threshold=0.07)
230  */
232 
233  private:
234  /** Rebuild the "expected" grid map. Used internally, do not call
235  */
236  void rebuildAverageMap();
237 
238 
239 
240  //protected:
241  public:
242  /** \name Virtual methods that the PF_implementations assume exist.
243  @{ */
244 
245  /** Return a pointer to the last robot pose in the i'th particle (or NULL if it's a path and it's empty). */
246  const TPose3D * getLastPose(const size_t i) const;
247 
248  void PF_SLAM_implementation_custom_update_particle_with_new_pose(
249  CParticleDataContent *particleData,
250  const TPose3D &newPose) const;
251 
252  // The base implementation is fine for this class.
253  // void PF_SLAM_implementation_replaceByNewParticleSet( ...
254 
255  bool PF_SLAM_implementation_doWeHaveValidObservations(
256  const CParticleList &particles,
257  const CSensoryFrame *sf) const;
258 
259  bool PF_SLAM_implementation_skipRobotMovement() const;
260 
261  /** Evaluate the observation likelihood for one particle at a given location */
262  double PF_SLAM_computeObservationLikelihoodForParticle(
263  const CParticleFilter::TParticleFilterOptions &PF_options,
264  const size_t particleIndexForMap,
265  const CSensoryFrame &observation,
266  const CPose3D &x ) const;
267  /** @} */
268 
269 
270  }; // End of class def.
272 
273  } // End of namespace
274 } // End of namespace
275 
276 #endif
size_t getNumberOfObservationsInSimplemap() const
Get the number of CSensoryFrame inserted into the internal member SFs.
The ICP algorithm configuration data.
Definition: CICP.h:58
This class stores any customizable set of metric maps.
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:35
Option set for KLD algorithm.
Definition: TKLDParams.h:24
STL namespace.
COccupancyGridMap2D::TLikelihoodOptions update_gridMapLikelihoodOptions
[update stage] If the likelihood is computed through the occupancy grid map, then this structure is p...
std::deque< TPose3D > robotPath
Declares a class for storing a collection of robot actions.
This class allows loading and storing values and vectors of different types from a configuration text...
A set of common data shared by PF implementations for both SLAM and localization. ...
CRBPFParticleData CParticleDataContent
This is the type inside the corresponding CParticleData class.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
#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...
float newInfoIndex
An index [0,1] measuring how much information an observation aports to the map (Typ.
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilt...
CICP::TConfigParams icp_params
ICP parameters, used only when "PF_algorithm=2" in the particle filter.
This template class declares the array of particles and its internal data, managing some memory-relat...
This class stores a sequence of pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:34
The struct for passing extra simulation parameters to the prediction/update stage when running a part...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:53
A class used to store a 2D pose.
Definition: CPose2D.h:36
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:69
The configuration of a particle filter.
Auxiliary class used in mrpt::slam::CMultiMetricMapPDF.
int pfOptimalProposal_mapSelection
[pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal") Select the map on whic...
Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
float ICPGlobalAlign_MinQuality
[prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum ...
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
A curiously recurring template pattern (CRTP) approach to providing the basic functionality of any CP...
With this struct options are provided to the observation likelihood computation process.



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014