1 #ifndef GRIDSLAMPROCESSOR_H     2 #define GRIDSLAMPROCESSOR_H    17 #include <gmapping/gridfastslam/gridfastslam_export.h>    86     typedef std::deque<GridSlamProcessor::TNode*> 
TNodeDeque;
    96       inline operator double()
 const {
return weight;}
   145     void setSensorMap(
const SensorMap& smap);
   146     void init(
unsigned int size, 
double xmin, 
double ymin, 
double xmax, 
double ymax, 
double delta, 
   148     void setMatchingParameters(
double urange, 
double range, 
double sigma, 
int kernsize, 
double lopt, 
double aopt, 
   149                                int iterations, 
double likelihoodSigma=1, 
double likelihoodGain=1, 
unsigned int likelihoodSkip=0);
   150     void setMotionModelParameters(
double srr, 
double srt, 
double str, 
double stt);
   151     void setUpdateDistances(
double linear, 
double angular, 
double resampleThreshold);
   156     bool processScan(
const RangeReading & reading, 
int adaptParticles=0);
   163     TNodeVector getTrajectories() 
const;
   164     void integrateScanSequence(
TNode* node);
   169     std::ofstream& outputStream();
   171     std::ostream& infoStream();
   173     inline const ParticleVector& 
getParticles()
 const {
return m_particles; }
   175     inline const std::vector<unsigned int>& 
getIndexes()
 const{
return m_indexes; }
   176     int getBestParticleIndex() 
const;
   178     virtual void onOdometryUpdate();
   179     virtual void onResampleUpdate();
   180     virtual void onScanmatchUpdate();
   205     MEMBER_PARAM_SET_GET(m_matcher, 
unsigned int, optRecursiveIterations, 
protected, 
public, 
public);
   245     PARAM_SET_GET(
double, minimumScore, 
protected, 
public, 
public);
   269     PARAM_SET_GET(
double, resampleThreshold, 
protected, 
public, 
public);
   280     PARAM_GET(
double, xmin, 
protected, 
public);
   281     PARAM_GET(
double, ymin, 
protected, 
public);
   282     PARAM_GET(
double, xmax, 
protected, 
public);
   283     PARAM_GET(
double, ymax, 
protected, 
public);
   285     PARAM_GET(
double, delta, 
protected, 
public);
   295     PARAM_SET_GET(
double, linearThresholdDistance, 
protected, 
public, 
public);
   298     PARAM_SET_GET(
double, angularThresholdDistance, 
protected, 
public, 
public);
   301     PARAM_SET_GET(
double, obsSigmaGain, 
protected, 
public, 
public);
   315     inline void scanMatch(
const double *plainReading);
   320     inline bool resample(
const double* plainReading, 
int adaptParticles, 
   325     void updateTreeWeights(
bool weightsAlreadyNormalized = 
false);
   327     double propagateWeights();
   331 typedef std::multimap<const GridSlamProcessor::TNode*, GridSlamProcessor::TNode*> 
TNodeMultimap;
   334 #include "gmapping/gridfastslam/gridslamprocessor.hxx" const char *const  *argv double delta
void normalize(const Iterator &begin, const Iterator &end)
std::vector< double > m_weights
const RangeReading * reading
#define PARAM_SET_GET(type, name, qualifier, setqualifier, getqualifier)
std::vector< GridSlamProcessor::TNode * > TNodeVector
std::vector< unsigned int > m_indexes
const std::vector< unsigned int > & getIndexes() const
OrientedPoint previousPose
unsigned int visitCounter
std::vector< Particle > ParticleVector
#define STRUCT_PARAM_SET_GET(member, type, name, qualifier, setqualifier, getqualifier)
std::deque< GridSlamProcessor::TNode * > TNodeDeque
std::multimap< const GridSlamProcessor::TNode *, GridSlamProcessor::TNode * > TNodeMultimap
const ParticleVector & getParticles() const
void resample(std::vector< int > &indexes, const WeightVector &weights, unsigned int nparticles=0)
ParticleVector m_particles
#define MEMBER_PARAM_SET_GET(member, type, name, qualifier, setqualifier, getqualifier)
OrientedPoint m_lastPartPose
std::ofstream m_outputStream
MotionModel m_motionModel
std::map< std::string, Sensor * > SensorMap
std::ostream & m_infoStream
void setUpdatePeriod(double p)
orientedpoint< double, double > OrientedPoint
#define PARAM_GET(type, name, qualifier, getqualifier)