Go to the documentation of this file.
46 const TPose3D* newPoseToBeInserted)
49 if (newPoseToBeInserted)
73 CMonteCarloLocalization2D::CMonteCarloLocalization2D(
size_t M)
81 const size_t i,
bool& is_valid_pose)
const
108 PF_SLAM_implementation_pfStandardProposal<mrpt::slam::detail::TPoseBin2D>(
159 PF_SLAM_implementation_pfAuxiliaryPFOptimal<mrpt::slam::detail::TPoseBin2D>(
171 const size_t particleIndexForMap,
const CSensoryFrame& observation,
185 it != observation.
end(); ++it)
198 *particleData =
TPose2D(newPose);
202 CParticleList& old_particles,
const vector<TPose3D>& newParticles,
203 const vector<double>& newParticlesWeight,
204 const vector<size_t>& newParticlesDerivedFromIdx)
const
208 size_t(newParticlesWeight.size()),
size_t(newParticles.size()));
219 const size_t N = newParticles.size();
220 old_particles.resize(N);
221 for (
size_t i = 0; i < N; i++)
223 old_particles[i].log_w = newParticlesWeight[i];
224 old_particles[i].d =
TPose2D(newParticles[i]);
230 const int particlesCount,
const double x_min,
const double x_max,
231 const double y_min,
const double y_max,
const double phi_min,
232 const double phi_max)
240 std::vector<double> freeCells_x, freeCells_y;
242 unsigned int xIdx1, xIdx2;
243 unsigned int yIdx1, yIdx2;
245 freeCells_x.reserve(sizeX * sizeY);
246 freeCells_y.reserve(sizeX * sizeY);
249 xIdx1 = max(0, theMap->
x2idx(x_min));
252 if (x_max < theMap->getXMax())
253 xIdx2 =
min(sizeX - 1, theMap->
x2idx(x_max));
257 yIdx1 = max(0, theMap->
y2idx(y_min));
260 if (y_max < theMap->getYMax())
261 yIdx2 =
min(sizeY - 1, theMap->
y2idx(y_max));
265 for (
unsigned int x = xIdx1;
x <= xIdx2;
x++)
266 for (
unsigned int y = yIdx1;
y <= yIdx2;
y++)
267 if (theMap->
getCell(
x,
y) >= freeCellsThreshold)
269 freeCells_x.push_back(theMap->
idx2x(
x));
270 freeCells_y.push_back(theMap->
idx2y(
y));
273 nFreeCells = freeCells_x.size();
283 for (
size_t i = 0; i < M; i++)
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
void PF_SLAM_implementation_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *actions, const mrpt::obs::CSensoryFrame *sf, const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const TKLDParams &KLD_options)
A generic implementation of the PF method "prediction_and_update_pfAuxiliaryPFStandard" (Auxiliary pa...
const_iterator end() const
Returns a constant iterator to the end of the list of observations: this is an example of usage:
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 nullptr) a new pose appe...
double phi
Orientation (rads)
mrpt::math::TPose3D getLastPose(const size_t i, bool &is_valid_pose) const override
Return the robot pose for the i'th particle.
mrpt::maps::TMetricMapList metricMaps
[update stage] Alternative way (if metricMap==nullptr): A metric map is supplied for each particle: T...
Option set for KLD algorithm.
double computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom)
Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
virtual ~CMonteCarloLocalization2D()
Destructor.
Declares a class for storing a collection of robot actions.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define THROW_EXCEPTION(msg)
#define ASSERT_(f)
Defines an assertion mechanism.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
This namespace contains representation of robot actions and observations.
void prediction_and_update_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command.
float idx2y(const size_t cy) const
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
unsigned int getSizeY() const
Returns the vertical size of grid map in cells count.
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...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Declares a virtual base class for all metric maps storage classes.
double drawUniform(const double Min, const double Max)
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm,...
const_iterator begin() const
Returns a constant iterator to the first observation: this is an example of usage:
int round(const T value)
Returns the closer integer (int) to x.
size_t particlesCount() const override
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
int x2idx(float x) const
Transform a coordinate value into a cell index.
float getYMin() const
Returns the "y" coordinate of top side of grid map.
void prediction_and_update_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command.
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Auxiliary structure used in KLD-sampling in particle filters.
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 override
Evaluate the observation likelihood for one particle at a given location.
std::deque< CObservation::Ptr >::const_iterator const_iterator
You can use CSensoryFrame::begin to get a iterator to the first element.
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,...
void PF_SLAM_implementation_custom_update_particle_with_new_pose(mrpt::math::TPose2D *particleData, const mrpt::math::TPose3D &newPose) const override
CParticleList m_particles
The array of particles.
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 override
float getResolution() const
Returns the resolution of the grid map.
double yaw
Yaw coordinate (rotation angle over Z axis).
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
TMonteCarloLocalizationParams options
MCL parameters.
float getXMin() const
Returns the "x" coordinate of left side of grid map.
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
This base provides a set of functions for maths stuff.
A class for storing an occupancy grid map.
unsigned int getSizeX() const
Returns the horizontal size of grid map in cells count.
A namespace of pseudo-random numbers generators of diferent distributions.
mrpt::maps::CMetricMap * metricMap
[update stage] Must be set to a metric map used to estimate the likelihood of observations
void setLoggerName(const std::string &name)
Set the name of the COutputLogger instance.
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command.
The configuration of a particle filter.
double KLD_binSize_XY
Parameters for the KLD adaptive sample size algorithm (see Dieter Fox's papers), which is used only i...
TKLDParams KLD_params
Parameters for dynamic sample size, KLD method.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |