Classes | Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
GridSlamProcessorThread Struct Reference

#include <gsp_thread.h>

Inheritance diagram for GridSlamProcessorThread:
Inheritance graph
[legend]

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< ParticleParticleVector
 
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< OrientedPointgetHypotheses ()
 
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
GridSlamProcessorclone () const
 
int getBestParticleIndex () const
 
const std::vector< unsigned int > & getIndexes () const
 
const ParticleVectorgetParticles () 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, bool, enlargeStep, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, bool, generateMap, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, gaussianSigma, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, lasamplerange, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, lasamplestep, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, laserMaxRange, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, likelihoodSigma, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, llsamplerange, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, double, llsamplestep, 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, double, usableRange, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, int, kernelSize, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, OrientedPoint, laserPose, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, unsigned int, likelihoodSkip, protected, public, public)
 
 MEMBER_PARAM_SET_GET (m_matcher, unsigned int, optRecursiveIterations, 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 *)
 

Private Attributes

double angularOdometryReliability
 
double angularUpdate
 
double astep
 
bool autosize
 
bool considerOdometryCovariance
 
double critscore
 
double delta
 
EventDeque eventBuffer
 
unsigned int eventBufferLength
 
std::string filename
 
bool generateMap
 
pthread_t gfs_thread
 
pthread_mutex_t hist_mutex
 
pthread_mutex_t hp_mutex
 
std::vector< OrientedPointhypotheses
 
pthread_mutex_t ind_mutex
 
std::vector< unsigned int > indexes
 
InputSensorStreaminput
 
int iterations
 
int kernelSize
 
double lasamplerange
 
double lasamplestep
 
double linearOdometryReliability
 
double linearUpdate
 
double llsamplerange
 
double llsamplestep
 
double lsigma
 
unsigned int lskip
 
double lstep
 
unsigned int m_argc
 
const char *const * m_argv
 
unsigned int mapTimer
 
unsigned int mapUpdateTime
 
double maxMove
 
double maxrange
 
double maxUrange
 
double ogain
 
bool onLine
 
std::string outfilename
 
int particles
 
std::ifstream plainStream
 
unsigned int randseed
 
bool readFromStdin
 
double regscore
 
double resampleThreshold
 
bool running
 
SensorMap sensorMap
 
double sigma
 
bool skipMatching
 
double srr
 
double srt
 
double str
 
double stt
 
std::vector< double > weightSums
 
double xmax
 
double xmin
 
double ymax
 
double ymin
 

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, delta, protected, public)
 
 PARAM_GET (double, neff, protected, public)
 
 PARAM_GET (double, xmax, protected, public)
 
 PARAM_GET (double, xmin, protected, public)
 
 PARAM_GET (double, ymax, protected, public)
 
 PARAM_GET (double, ymin, protected, public)
 
 PARAM_SET_GET (double, angularThresholdDistance, protected, public, public)
 
 PARAM_SET_GET (double, critScore, protected, public, public)
 
 PARAM_SET_GET (double, linearThresholdDistance, protected, public, public)
 
 PARAM_SET_GET (double, maxMove, protected, public, public)
 
 PARAM_SET_GET (double, obsSigmaGain, protected, public, public)
 
 PARAM_SET_GET (double, regScore, protected, public, public)
 
 PARAM_SET_GET (double, resampleThreshold, 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_
 

Detailed Description

Definition at line 44 of file gsp_thread.h.

Member Typedef Documentation

◆ EventDeque

Definition at line 74 of file gsp_thread.h.

Constructor & Destructor Documentation

◆ GridSlamProcessorThread()

GridSlamProcessorThread::GridSlamProcessorThread ( )

Definition at line 188 of file gsp_thread.cpp.

◆ ~GridSlamProcessorThread()

GridSlamProcessorThread::~GridSlamProcessorThread ( )

Definition at line 267 of file gsp_thread.cpp.

Member Function Documentation

◆ addEvent()

void GridSlamProcessorThread::addEvent ( GridSlamProcessorThread::Event e)
private

Definition at line 604 of file gsp_thread.cpp.

◆ boundingBox()

OrientedPoint GridSlamProcessorThread::boundingBox ( SensorLog log,
double &  xmin,
double &  ymin,
double &  xmax,
double &  ymax 
) const

Definition at line 634 of file gsp_thread.cpp.

◆ fastslamthread()

void * GridSlamProcessorThread::fastslamthread ( GridSlamProcessorThread gpt)
static

Definition at line 277 of file gsp_thread.cpp.

◆ getEvents()

GridSlamProcessorThread::EventDeque GridSlamProcessorThread::getEvents ( )

Definition at line 615 of file gsp_thread.cpp.

◆ getHypotheses()

std::vector< OrientedPoint > GridSlamProcessorThread::getHypotheses ( )

Definition at line 485 of file gsp_thread.cpp.

◆ getIndexes()

std::vector< unsigned int > GridSlamProcessorThread::getIndexes ( )

Definition at line 492 of file gsp_thread.cpp.

◆ init()

int GridSlamProcessorThread::init ( int  argc,
const char *const *  argv 
)

Definition at line 36 of file gsp_thread.cpp.

◆ isRunning()

bool GridSlamProcessorThread::isRunning ( ) const
inline

Definition at line 99 of file gsp_thread.h.

◆ loadFiles()

int GridSlamProcessorThread::loadFiles ( const char *  fn = 0)

Definition at line 153 of file gsp_thread.cpp.

◆ onOdometryUpdate()

void GridSlamProcessorThread::onOdometryUpdate ( )
virtual

Reimplemented from GMapping::GridSlamProcessor.

Definition at line 516 of file gsp_thread.cpp.

◆ onResampleUpdate()

void GridSlamProcessorThread::onResampleUpdate ( )
virtual

Reimplemented from GMapping::GridSlamProcessor.

Definition at line 537 of file gsp_thread.cpp.

◆ onScanmatchUpdate()

void GridSlamProcessorThread::onScanmatchUpdate ( )
virtual

Reimplemented from GMapping::GridSlamProcessor.

Definition at line 555 of file gsp_thread.cpp.

◆ setEventBufferSize()

void GridSlamProcessorThread::setEventBufferSize ( unsigned int  length)

Definition at line 630 of file gsp_thread.cpp.

◆ setMapUpdateTime()

void GridSlamProcessorThread::setMapUpdateTime ( unsigned int  ut)
inline

Definition at line 98 of file gsp_thread.h.

◆ start()

void GridSlamProcessorThread::start ( )

Definition at line 499 of file gsp_thread.cpp.

◆ stop()

void GridSlamProcessorThread::stop ( )

Definition at line 506 of file gsp_thread.cpp.

◆ syncOdometryUpdate()

void GridSlamProcessorThread::syncOdometryUpdate ( )
virtual

Definition at line 595 of file gsp_thread.cpp.

◆ syncResampleUpdate()

void GridSlamProcessorThread::syncResampleUpdate ( )
virtual

Definition at line 598 of file gsp_thread.cpp.

◆ syncScanmatchUpdate()

void GridSlamProcessorThread::syncScanmatchUpdate ( )
virtual

Definition at line 601 of file gsp_thread.cpp.

Member Data Documentation

◆ angularOdometryReliability

double GridSlamProcessorThread::angularOdometryReliability
private

Definition at line 149 of file gsp_thread.h.

◆ angularUpdate

double GridSlamProcessorThread::angularUpdate
private

Definition at line 159 of file gsp_thread.h.

◆ astep

double GridSlamProcessorThread::astep
private

Definition at line 136 of file gsp_thread.h.

◆ autosize

bool GridSlamProcessorThread::autosize
private

Definition at line 126 of file gsp_thread.h.

◆ considerOdometryCovariance

bool GridSlamProcessorThread::considerOdometryCovariance
private

Definition at line 170 of file gsp_thread.h.

◆ critscore

double GridSlamProcessorThread::critscore
private

Definition at line 139 of file gsp_thread.h.

◆ delta

double GridSlamProcessorThread::delta
private

Definition at line 127 of file gsp_thread.h.

◆ eventBuffer

EventDeque GridSlamProcessorThread::eventBuffer
private

Definition at line 104 of file gsp_thread.h.

◆ eventBufferLength

unsigned int GridSlamProcessorThread::eventBufferLength
private

Definition at line 106 of file gsp_thread.h.

◆ filename

std::string GridSlamProcessorThread::filename
private

Definition at line 119 of file gsp_thread.h.

◆ generateMap

bool GridSlamProcessorThread::generateMap
private

Definition at line 169 of file gsp_thread.h.

◆ gfs_thread

pthread_t GridSlamProcessorThread::gfs_thread
private

Definition at line 115 of file gsp_thread.h.

◆ hist_mutex

pthread_mutex_t GridSlamProcessorThread::hist_mutex
private

Definition at line 114 of file gsp_thread.h.

◆ hp_mutex

pthread_mutex_t GridSlamProcessorThread::hp_mutex
private

Definition at line 114 of file gsp_thread.h.

◆ hypotheses

std::vector<OrientedPoint> GridSlamProcessorThread::hypotheses
private

Definition at line 111 of file gsp_thread.h.

◆ ind_mutex

pthread_mutex_t GridSlamProcessorThread::ind_mutex
private

Definition at line 114 of file gsp_thread.h.

◆ indexes

std::vector<unsigned int> GridSlamProcessorThread::indexes
private

Definition at line 112 of file gsp_thread.h.

◆ input

InputSensorStream* GridSlamProcessorThread::input
private

Definition at line 165 of file gsp_thread.h.

◆ iterations

int GridSlamProcessorThread::iterations
private

Definition at line 138 of file gsp_thread.h.

◆ kernelSize

int GridSlamProcessorThread::kernelSize
private

Definition at line 137 of file gsp_thread.h.

◆ lasamplerange

double GridSlamProcessorThread::lasamplerange
private

Definition at line 146 of file gsp_thread.h.

◆ lasamplestep

double GridSlamProcessorThread::lasamplestep
private

Definition at line 147 of file gsp_thread.h.

◆ linearOdometryReliability

double GridSlamProcessorThread::linearOdometryReliability
private

Definition at line 148 of file gsp_thread.h.

◆ linearUpdate

double GridSlamProcessorThread::linearUpdate
private

Definition at line 160 of file gsp_thread.h.

◆ llsamplerange

double GridSlamProcessorThread::llsamplerange
private

Definition at line 146 of file gsp_thread.h.

◆ llsamplestep

double GridSlamProcessorThread::llsamplestep
private

Definition at line 147 of file gsp_thread.h.

◆ lsigma

double GridSlamProcessorThread::lsigma
private

Definition at line 144 of file gsp_thread.h.

◆ lskip

unsigned int GridSlamProcessorThread::lskip
private

Definition at line 141 of file gsp_thread.h.

◆ lstep

double GridSlamProcessorThread::lstep
private

Definition at line 135 of file gsp_thread.h.

◆ m_argc

unsigned int GridSlamProcessorThread::m_argc
private

Definition at line 175 of file gsp_thread.h.

◆ m_argv

const char* const * GridSlamProcessorThread::m_argv
private

Definition at line 174 of file gsp_thread.h.

◆ mapTimer

unsigned int GridSlamProcessorThread::mapTimer
private

Definition at line 108 of file gsp_thread.h.

◆ mapUpdateTime

unsigned int GridSlamProcessorThread::mapUpdateTime
private

Definition at line 107 of file gsp_thread.h.

◆ maxMove

double GridSlamProcessorThread::maxMove
private

Definition at line 140 of file gsp_thread.h.

◆ maxrange

double GridSlamProcessorThread::maxrange
private

Definition at line 132 of file gsp_thread.h.

◆ maxUrange

double GridSlamProcessorThread::maxUrange
private

Definition at line 133 of file gsp_thread.h.

◆ ogain

double GridSlamProcessorThread::ogain
private

Definition at line 145 of file gsp_thread.h.

◆ onLine

bool GridSlamProcessorThread::onLine
private

Definition at line 168 of file gsp_thread.h.

◆ outfilename

std::string GridSlamProcessorThread::outfilename
private

Definition at line 120 of file gsp_thread.h.

◆ particles

int GridSlamProcessorThread::particles
private

Definition at line 155 of file gsp_thread.h.

◆ plainStream

std::ifstream GridSlamProcessorThread::plainStream
private

Definition at line 166 of file gsp_thread.h.

◆ randseed

unsigned int GridSlamProcessorThread::randseed
private

Definition at line 171 of file gsp_thread.h.

◆ readFromStdin

bool GridSlamProcessorThread::readFromStdin
private

Definition at line 167 of file gsp_thread.h.

◆ regscore

double GridSlamProcessorThread::regscore
private

Definition at line 134 of file gsp_thread.h.

◆ resampleThreshold

double GridSlamProcessorThread::resampleThreshold
private

Definition at line 128 of file gsp_thread.h.

◆ running

bool GridSlamProcessorThread::running
private

Definition at line 116 of file gsp_thread.h.

◆ sensorMap

SensorMap GridSlamProcessorThread::sensorMap
private

Definition at line 163 of file gsp_thread.h.

◆ sigma

double GridSlamProcessorThread::sigma
private

Definition at line 131 of file gsp_thread.h.

◆ skipMatching

bool GridSlamProcessorThread::skipMatching
private

Definition at line 156 of file gsp_thread.h.

◆ srr

double GridSlamProcessorThread::srr
private

Definition at line 153 of file gsp_thread.h.

◆ srt

double GridSlamProcessorThread::srt
private

Definition at line 153 of file gsp_thread.h.

◆ str

double GridSlamProcessorThread::str
private

Definition at line 153 of file gsp_thread.h.

◆ stt

double GridSlamProcessorThread::stt
private

Definition at line 153 of file gsp_thread.h.

◆ weightSums

std::vector<double> GridSlamProcessorThread::weightSums
private

Definition at line 113 of file gsp_thread.h.

◆ xmax

double GridSlamProcessorThread::xmax
private

Definition at line 124 of file gsp_thread.h.

◆ xmin

double GridSlamProcessorThread::xmin
private

Definition at line 122 of file gsp_thread.h.

◆ ymax

double GridSlamProcessorThread::ymax
private

Definition at line 125 of file gsp_thread.h.

◆ ymin

double GridSlamProcessorThread::ymin
private

Definition at line 123 of file gsp_thread.h.


The documentation for this struct was generated from the following files:


openslam_gmapping
Author(s): Cyrill Stachniss, Udo Frese, Giorgio Grisetti, Wolfram Burgard
autogenerated on Thu Oct 19 2023 02:25:51