#include <gsp_thread.h>

| Classes | |
| struct | DoneEvent | 
| struct | Event | 
| struct | MapEvent | 
| struct | ParticleMoveEvent | 
| struct | ResampleEvent | 
| struct | TruePosEvent | 
| Public Types | |
| typedef deque< Event * > | EventDeque | 
|  Public Types inherited from GMapping::GridSlamProcessor | |
| typedef std::vector< Particle > | ParticleVector | 
| typedef std::deque< GridSlamProcessor::TNode * > | TNodeDeque | 
| typedef std::vector< GridSlamProcessor::TNode * > | TNodeVector | 
| Public Member Functions | |
| OrientedPoint | boundingBox (SensorLog *log, double &xmin, double &ymin, double &xmax, double &ymax) const | 
| EventDeque | getEvents () | 
| std::vector< OrientedPoint > | getHypotheses () | 
| std::vector< unsigned int > | getIndexes () | 
| GridSlamProcessorThread () | |
| int | init (int argc, const char *const *argv) | 
| bool | isRunning () const | 
| int | loadFiles (const char *fn=0) | 
| virtual void | onOdometryUpdate () | 
| virtual void | onResampleUpdate () | 
| virtual void | onScanmatchUpdate () | 
| void | setEventBufferSize (unsigned int length) | 
| void | setMapUpdateTime (unsigned int ut) | 
| void | start () | 
| void | stop () | 
| virtual void | syncOdometryUpdate () | 
| virtual void | syncResampleUpdate () | 
| virtual void | syncScanmatchUpdate () | 
| ~GridSlamProcessorThread () | |
|  Public Member Functions inherited from GMapping::GridSlamProcessor | |
| GridSlamProcessor * | clone () const | 
| int | getBestParticleIndex () const | 
| const std::vector< unsigned int > & | getIndexes () const | 
| const ParticleVector & | getParticles () const | 
| TNodeVector | getTrajectories () const | 
| GridSlamProcessor () | |
| GridSlamProcessor (std::ostream &infoStr) | |
| std::ostream & | infoStream () | 
| void | init (unsigned int size, double xmin, double ymin, double xmax, double ymax, double delta, OrientedPoint initialPose=OrientedPoint(0, 0, 0)) | 
| void | integrateScanSequence (TNode *node) | 
| MEMBER_PARAM_SET_GET (m_matcher, double, laserMaxRange, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, usableRange, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, gaussianSigma, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, likelihoodSigma, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, int, kernelSize, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, optAngularDelta, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, optLinearDelta, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, unsigned int, optRecursiveIterations, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, unsigned int, likelihoodSkip, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, llsamplerange, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, lasamplerange, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, llsamplestep, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, double, lasamplestep, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, bool, generateMap, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, bool, enlargeStep, protected, public, public) | |
| MEMBER_PARAM_SET_GET (m_matcher, OrientedPoint, laserPose, protected, public, public) | |
| std::ofstream & | outputStream () | 
| PARAM_SET_GET (double, minimumScore, protected, public, public) | |
| bool | processScan (const RangeReading &reading, int adaptParticles=0) | 
| void | processTruePos (const OdometryReading &odometry) | 
| void | setMatchingParameters (double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations, double likelihoodSigma=1, double likelihoodGain=1, unsigned int likelihoodSkip=0) | 
| void | setMotionModelParameters (double srr, double srt, double str, double stt) | 
| void | setSensorMap (const SensorMap &smap) | 
| void | setUpdateDistances (double linear, double angular, double resampleThreshold) | 
| void | setUpdatePeriod (double p) | 
| STRUCT_PARAM_SET_GET (m_motionModel, double, srr, protected, public, public) | |
| STRUCT_PARAM_SET_GET (m_motionModel, double, srt, protected, public, public) | |
| STRUCT_PARAM_SET_GET (m_motionModel, double, str, protected, public, public) | |
| STRUCT_PARAM_SET_GET (m_motionModel, double, stt, protected, public, public) | |
| virtual | ~GridSlamProcessor () | 
| Static Public Member Functions | |
| static void * | fastslamthread (GridSlamProcessorThread *gpt) | 
| Private Member Functions | |
| void | addEvent (Event *) | 
| Additional Inherited Members | |
|  Public Attributes inherited from GMapping::GridSlamProcessor | |
| ScanMatcher | m_matcher | 
|  Protected Member Functions inherited from GMapping::GridSlamProcessor | |
| GridSlamProcessor (const GridSlamProcessor &gsp) | |
| PARAM_GET (double, neff, protected, public) | |
| PARAM_GET (double, xmin, protected, public) | |
| PARAM_GET (double, ymin, protected, public) | |
| PARAM_GET (double, xmax, protected, public) | |
| PARAM_GET (double, ymax, protected, public) | |
| PARAM_GET (double, delta, protected, public) | |
| PARAM_SET_GET (double, resampleThreshold, protected, public, public) | |
| PARAM_SET_GET (double, regScore, protected, public, public) | |
| PARAM_SET_GET (double, critScore, protected, public, public) | |
| PARAM_SET_GET (double, maxMove, protected, public, public) | |
| PARAM_SET_GET (double, linearThresholdDistance, protected, public, public) | |
| PARAM_SET_GET (double, angularThresholdDistance, protected, public, public) | |
| PARAM_SET_GET (double, obsSigmaGain, protected, public, public) | |
|  Protected Attributes inherited from GMapping::GridSlamProcessor | |
| double | last_update_time_ | 
| double | m_angularDistance | 
| unsigned int | m_beams | 
| int | m_count | 
| std::vector< unsigned int > | m_indexes | 
| std::ostream & | m_infoStream | 
| OrientedPoint | m_lastPartPose | 
| double | m_linearDistance | 
| MotionModel | m_motionModel | 
| OrientedPoint | m_odoPose | 
| std::ofstream | m_outputStream | 
| ParticleVector | m_particles | 
| OrientedPoint | m_pose | 
| int | m_readingCount | 
| std::vector< double > | m_weights | 
| double | period_ | 
Definition at line 44 of file gsp_thread.h.
| typedef deque<Event*> GridSlamProcessorThread::EventDeque | 
Definition at line 74 of file gsp_thread.h.
| GridSlamProcessorThread::GridSlamProcessorThread | ( | ) | 
Definition at line 188 of file gsp_thread.cpp.
| GridSlamProcessorThread::~GridSlamProcessorThread | ( | ) | 
Definition at line 267 of file gsp_thread.cpp.
| 
 | private | 
Definition at line 604 of file gsp_thread.cpp.
| OrientedPoint GridSlamProcessorThread::boundingBox | ( | SensorLog * | log, | 
| double & | xmin, | ||
| double & | ymin, | ||
| double & | xmax, | ||
| double & | ymax | ||
| ) | const | 
Definition at line 634 of file gsp_thread.cpp.
| 
 | static | 
Definition at line 277 of file gsp_thread.cpp.
| GridSlamProcessorThread::EventDeque GridSlamProcessorThread::getEvents | ( | ) | 
Definition at line 615 of file gsp_thread.cpp.
| std::vector< OrientedPoint > GridSlamProcessorThread::getHypotheses | ( | ) | 
Definition at line 485 of file gsp_thread.cpp.
| std::vector< unsigned int > GridSlamProcessorThread::getIndexes | ( | ) | 
Definition at line 492 of file gsp_thread.cpp.
| int GridSlamProcessorThread::init | ( | int | argc, | 
| const char *const * | argv | ||
| ) | 
Definition at line 36 of file gsp_thread.cpp.
| 
 | inline | 
Definition at line 99 of file gsp_thread.h.
| int GridSlamProcessorThread::loadFiles | ( | const char * | fn = 0 | ) | 
Definition at line 153 of file gsp_thread.cpp.
| 
 | virtual | 
Reimplemented from GMapping::GridSlamProcessor.
Definition at line 516 of file gsp_thread.cpp.
| 
 | virtual | 
Reimplemented from GMapping::GridSlamProcessor.
Definition at line 537 of file gsp_thread.cpp.
| 
 | virtual | 
Reimplemented from GMapping::GridSlamProcessor.
Definition at line 555 of file gsp_thread.cpp.
| void GridSlamProcessorThread::setEventBufferSize | ( | unsigned int | length | ) | 
Definition at line 630 of file gsp_thread.cpp.
| 
 | inline | 
Definition at line 98 of file gsp_thread.h.
| void GridSlamProcessorThread::start | ( | ) | 
Definition at line 499 of file gsp_thread.cpp.
| void GridSlamProcessorThread::stop | ( | ) | 
Definition at line 506 of file gsp_thread.cpp.
| 
 | virtual | 
Definition at line 595 of file gsp_thread.cpp.
| 
 | virtual | 
Definition at line 598 of file gsp_thread.cpp.
| 
 | virtual | 
Definition at line 601 of file gsp_thread.cpp.
| 
 | private | 
Definition at line 149 of file gsp_thread.h.
| 
 | private | 
Definition at line 159 of file gsp_thread.h.
| 
 | private | 
Definition at line 136 of file gsp_thread.h.
| 
 | private | 
Definition at line 126 of file gsp_thread.h.
| 
 | private | 
Definition at line 170 of file gsp_thread.h.
| 
 | private | 
Definition at line 139 of file gsp_thread.h.
| 
 | private | 
Definition at line 127 of file gsp_thread.h.
| 
 | private | 
Definition at line 104 of file gsp_thread.h.
| 
 | private | 
Definition at line 106 of file gsp_thread.h.
| 
 | private | 
Definition at line 119 of file gsp_thread.h.
| 
 | private | 
Definition at line 169 of file gsp_thread.h.
| 
 | private | 
Definition at line 115 of file gsp_thread.h.
| 
 | private | 
Definition at line 114 of file gsp_thread.h.
| 
 | private | 
Definition at line 114 of file gsp_thread.h.
| 
 | private | 
Definition at line 111 of file gsp_thread.h.
| 
 | private | 
Definition at line 114 of file gsp_thread.h.
| 
 | private | 
Definition at line 112 of file gsp_thread.h.
| 
 | private | 
Definition at line 165 of file gsp_thread.h.
| 
 | private | 
Definition at line 138 of file gsp_thread.h.
| 
 | private | 
Definition at line 137 of file gsp_thread.h.
| 
 | private | 
Definition at line 146 of file gsp_thread.h.
| 
 | private | 
Definition at line 147 of file gsp_thread.h.
| 
 | private | 
Definition at line 148 of file gsp_thread.h.
| 
 | private | 
Definition at line 160 of file gsp_thread.h.
| 
 | private | 
Definition at line 146 of file gsp_thread.h.
| 
 | private | 
Definition at line 147 of file gsp_thread.h.
| 
 | private | 
Definition at line 144 of file gsp_thread.h.
| 
 | private | 
Definition at line 141 of file gsp_thread.h.
| 
 | private | 
Definition at line 135 of file gsp_thread.h.
| 
 | private | 
Definition at line 175 of file gsp_thread.h.
| 
 | private | 
Definition at line 174 of file gsp_thread.h.
| 
 | private | 
Definition at line 108 of file gsp_thread.h.
| 
 | private | 
Definition at line 107 of file gsp_thread.h.
| 
 | private | 
Definition at line 140 of file gsp_thread.h.
| 
 | private | 
Definition at line 132 of file gsp_thread.h.
| 
 | private | 
Definition at line 133 of file gsp_thread.h.
| 
 | private | 
Definition at line 145 of file gsp_thread.h.
| 
 | private | 
Definition at line 168 of file gsp_thread.h.
| 
 | private | 
Definition at line 120 of file gsp_thread.h.
| 
 | private | 
Definition at line 155 of file gsp_thread.h.
| 
 | private | 
Definition at line 166 of file gsp_thread.h.
| 
 | private | 
Definition at line 171 of file gsp_thread.h.
| 
 | private | 
Definition at line 167 of file gsp_thread.h.
| 
 | private | 
Definition at line 134 of file gsp_thread.h.
| 
 | private | 
Definition at line 128 of file gsp_thread.h.
| 
 | private | 
Definition at line 116 of file gsp_thread.h.
| 
 | private | 
Definition at line 163 of file gsp_thread.h.
| 
 | private | 
Definition at line 131 of file gsp_thread.h.
| 
 | private | 
Definition at line 156 of file gsp_thread.h.
| 
 | private | 
Definition at line 153 of file gsp_thread.h.
| 
 | private | 
Definition at line 153 of file gsp_thread.h.
| 
 | private | 
Definition at line 153 of file gsp_thread.h.
| 
 | private | 
Definition at line 153 of file gsp_thread.h.
| 
 | private | 
Definition at line 113 of file gsp_thread.h.
| 
 | private | 
Definition at line 124 of file gsp_thread.h.
| 
 | private | 
Definition at line 122 of file gsp_thread.h.
| 
 | private | 
Definition at line 125 of file gsp_thread.h.
| 
 | private | 
Definition at line 123 of file gsp_thread.h.