46 const TPose3D *newPoseToBeInserted)
49 if (newPoseToBeInserted)
72 CMonteCarloLocalization2D::CMonteCarloLocalization2D(
size_t M ) :
75 this->setLoggerName(
"CMonteCarloLocalization2D");
116 PF_SLAM_implementation_pfStandardProposal<mrpt::slam::detail::TPoseBin2D>(actions, sf, PF_options,
options.
KLD_params);
140 PF_SLAM_implementation_pfAuxiliaryPFStandard<mrpt::slam::detail::TPoseBin2D>(actions, sf, PF_options,
options.
KLD_params);
165 PF_SLAM_implementation_pfAuxiliaryPFOptimal<mrpt::slam::detail::TPoseBin2D>(actions, sf, PF_options,
options.
KLD_params);
176 const size_t particleIndexForMap,
190 ret += map->computeObservationLikelihood( it->pointer(),
x );
206 CParticleList &old_particles,
207 const vector<TPose3D> &newParticles,
208 const vector<double> &newParticlesWeight,
209 const vector<size_t> &newParticlesDerivedFromIdx )
const 212 ASSERT_EQUAL_(
size_t(newParticlesWeight.size()),
size_t(newParticles.size()));
222 const size_t N = newParticles.size();
223 old_particles.resize(N);
224 for (
size_t i=0;i<N;i++)
226 old_particles[i].log_w = newParticlesWeight[i];
233 const double freeCellsThreshold ,
234 const int particlesCount ,
239 const double phi_min,
240 const double phi_max)
249 std::vector<double> freeCells_x,freeCells_y;
251 unsigned int xIdx1,xIdx2;
252 unsigned int yIdx1,yIdx2;
254 freeCells_x.reserve( sizeX * sizeY );
255 freeCells_y.reserve( sizeX * sizeY );
258 xIdx1 = max(0, theMap->
x2idx( x_min ) );
260 if (x_max<theMap->getXMax())
261 xIdx2 =
min(sizeX-1, theMap->
x2idx( x_max ) );
262 else xIdx2 = sizeX-1;
264 yIdx1 = max(0, theMap->
y2idx( y_min ) );
266 if (y_max<theMap->getYMax())
267 yIdx2 =
min(sizeY-1, theMap->
y2idx( y_max ) );
268 else yIdx2 = sizeY-1;
271 for (
unsigned int x=xIdx1;
x<=xIdx2;
x++)
272 for (
unsigned int y=yIdx1;
y<=yIdx2;
y++)
273 if (theMap->
getCell(
x,
y)>=freeCellsThreshold)
275 freeCells_x.push_back(theMap->
idx2x(
x));
276 freeCells_y.push_back(theMap->
idx2y(
y));
279 nFreeCells = freeCells_x.size();
296 for (
size_t i=0;i<M;i++)
#define ASSERT_EQUAL_(__A, __B)
A namespace of pseudo-random numbers genrators of diferent distributions.
double drawUniform(const double Min, const double Max)
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, scaled to the selected range.
double x() const
Common members of all points & poses classes.
size_t particlesCount() const MRPT_OVERRIDE
float getYMin() const
Returns the "y" coordinate of top side of grid map.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
void PF_SLAM_implementation_replaceByNewParticleSet(CParticleList &old_particles, const std::vector< mrpt::math::TPose3D > &newParticles, const std::vector< double > &newParticlesWeight, const std::vector< size_t > &newParticlesDerivedFromIdx) const
void resetUniformFreeSpace(mrpt::maps::COccupancyGridMap2D *theMap, const double freeCellsThreshold=0.7, const int particlesCount=-1, const double x_min=-1e10f, const double x_max=1e10f, const double y_min=-1e10f, const double y_max=1e10f, const double phi_min=-M_PI, const double phi_max=M_PI)
Reset the PDF to an uniformly distributed one, but only in the free-space of a given 2D occupancy-gri...
float getResolution() const
Returns the resolution of the grid map.
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
#define THROW_EXCEPTION(msg)
BASE_IMPEXP CRandomGenerator randomGenerator
A static instance of a CRandomGenerator class, for use in single-thread applications.
double PF_SLAM_computeObservationLikelihoodForParticle(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const size_t particleIndexForMap, const mrpt::obs::CSensoryFrame &observation, const mrpt::poses::CPose3D &x) const
Evaluate the observation likelihood for one particle at a given location.
This file contains the implementations of the template members declared in mrpt::slam::PF_implementat...
Option set for KLD algorithm.
TMonteCarloLocalizationParams options
MCL parameters.
mrpt::math::TPose3D getLastPose(const size_t i, bool &pose_is_valid) const MRPT_OVERRIDE
Return the last robot pose in the i'th particle; pose_is_valid will be false if particle is a path an...
void clear()
Free all the memory associated to m_particles, and set the number of parts = 0.
mrpt::maps::TMetricMapList metricMaps
[update stage] Alternative way (if metricMap==NULL): A metric map is supplied for each particle: Ther...
double yaw
Yaw coordinate (rotation angle over Z axis).
void PF_SLAM_implementation_custom_update_particle_with_new_pose(CParticleDataContent *particleData, const mrpt::math::TPose3D &newPose) const
mrpt::maps::CMetricMap * metricMap
[update stage] Must be set to a metric map used to estimate the likelihood of observations ...
Declares a class for storing a collection of robot actions.
std::deque< CObservationPtr >::const_iterator const_iterator
You can use CSensoryFrame::begin to get a iterator to the first element.
const_iterator begin() const
Returns a constant iterator to the first observation: this is an example of usage: ...
CParticleList m_particles
The array of particles.
This base provides a set of functions for maths stuff.
float getXMin() const
Returns the "x" coordinate of left side of grid map.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
virtual ~CMonteCarloLocalization2D()
Destructor.
This namespace contains representation of robot actions and observations.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
unsigned int getSizeX() const
Returns the horizontal size of grid map in cells count.
double KLD_binSize_XY
Parameters for the KLD adaptive sample size algorithm (see Dieter Fox's papers), which is used only i...
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Auxiliary structure used in KLD-sampling in particle filters.
A class for storing an occupancy grid map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
const double & phi() const
Get the phi angle of the 2D pose (in radians)
The configuration of a particle filter.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
void prediction_and_update_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
float idx2y(const size_t cy) const
int round(const T value)
Returns the closer integer (int) to x.
void KLF_loadBinFromParticle(mrpt::slam::detail::TPoseBin2D &outBin, const TKLDParams &opts, const CMonteCarloLocalization2D::CParticleDataContent *currentParticleValue, const TPose3D *newPoseToBeInserted)
Fills out a "TPoseBin2D" variable, given a path hypotesis and (if not set to NULL) a new pose appende...
void prediction_and_update_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
const_iterator end() const
Returns a constant iterator to the end of the list of observations: this is an example of usage: ...
unsigned int getSizeY() const
Returns the vertical size of grid map in cells count.
int x2idx(float x) const
Transform a coordinate value into a cell index.
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
TKLDParams KLD_params
Parameters for dynamic sample size, KLD method.
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)
Update the m_particles, predicting the posterior of robot pose and map after a movement command...