gsp_thread.cpp
Go to the documentation of this file.
1 /*****************************************************************
2  *
3  * This file is part of the GMAPPING project
4  *
5  * GMAPPING Copyright (c) 2004 Giorgio Grisetti,
6  * Cyrill Stachniss, and Wolfram Burgard
7  *
8  * This software is licensed under the "Creative Commons
9  * License (Attribution-NonCommercial-ShareAlike 2.0)"
10  * and is copyrighted by Giorgio Grisetti, Cyrill Stachniss,
11  * and Wolfram Burgard.
12  *
13  * Further information on this license can be found at:
14  * http://creativecommons.org/licenses/by-nc-sa/2.0/
15  *
16  * GMAPPING is distributed in the hope that it will be useful,
17  * but WITHOUT ANY WARRANTY; without even the implied
18  * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
19  * PURPOSE.
20  *
21  *****************************************************************/
22 
23 
24 #include "gsp_thread.h"
25 #include <utils/commandline.h>
26 #include <utils/stat.h>
27 #include <configfile/configfile.h>
28 
29 #ifdef CARMEN_SUPPORT
31 #endif
32 
33 #define DEBUG cout << __PRETTY_FUNCTION__
34 
35 using namespace std;
36 
37 int GridSlamProcessorThread::init(int argc, const char * const * argv){
38  m_argc=argc;
39  m_argv=argv;
40  std::string configfilename;
41  std::string ebuf="not_set";
42 
43  CMD_PARSE_BEGIN_SILENT(1,argc);
44  parseStringSilent("-cfg",configfilename);
46 
47  if (configfilename.length()>0){
48  ConfigFile cfg(configfilename);
49 
50  filename = (std::string) cfg.value("gfs","filename",filename);
51  outfilename = (std::string) cfg.value("gfs","outfilename",outfilename);
52  xmin = cfg.value("gfs","xmin", xmin);
53  xmax = cfg.value("gfs","xmax",xmax);
54  ymin = cfg.value("gfs","ymin",ymin);
55  ymax = cfg.value("gfs","ymax",ymax);
56  delta = cfg.value("gfs","delta",delta);
57  maxrange = cfg.value("gfs","maxrange",maxrange);
58  maxUrange = cfg.value("gfs","maxUrange",maxUrange);
59  regscore = cfg.value("gfs","regscore",regscore);
60  critscore = cfg.value("gfs","critscore",critscore);
61  kernelSize = cfg.value("gfs","kernelSize",kernelSize);
62  sigma = cfg.value("gfs","sigma",sigma);
63  iterations = cfg.value("gfs","iterations",iterations);
64  lstep = cfg.value("gfs","lstep",lstep);
65  astep = cfg.value("gfs","astep",astep);
66  maxMove = cfg.value("gfs","maxMove",maxMove);
67  srr = cfg.value("gfs","srr", srr);
68  srt = cfg.value("gfs","srt", srt);
69  str = cfg.value("gfs","str", str);
70  stt = cfg.value("gfs","stt", stt);
71  particles = cfg.value("gfs","particles",particles);
72  angularUpdate = cfg.value("gfs","angularUpdate", angularUpdate);
73  linearUpdate = cfg.value("gfs","linearUpdate", linearUpdate);
74  lsigma = cfg.value("gfs","lsigma", lsigma);
75  ogain = cfg.value("gfs","lobsGain", ogain);
76  lskip = (int)cfg.value("gfs","lskip", lskip);
77  mapUpdateTime = cfg.value("gfs","mapUpdate", mapUpdateTime);
78  randseed = cfg.value("gfs","randseed", randseed);
79  autosize = cfg.value("gfs","autosize", autosize);
80  readFromStdin = cfg.value("gfs","stdin", readFromStdin);
81  resampleThreshold = cfg.value("gfs","resampleThreshold", resampleThreshold);
82  skipMatching = cfg.value("gfs","skipMatching", skipMatching);
83  onLine = cfg.value("gfs","onLine", onLine);
84  generateMap = cfg.value("gfs","generateMap", generateMap);
85  m_minimumScore = cfg.value("gfs","minimumScore", m_minimumScore);
86  llsamplerange = cfg.value("gfs","llsamplerange", llsamplerange);
87  lasamplerange = cfg.value("gfs","lasamplerange",lasamplerange );
88  llsamplestep = cfg.value("gfs","llsamplestep", llsamplestep);
89  lasamplestep = cfg.value("gfs","lasamplestep", lasamplestep);
90  linearOdometryReliability = cfg.value("gfs","linearOdometryReliability",linearOdometryReliability);
91  angularOdometryReliability = cfg.value("gfs","angularOdometryReliability",angularOdometryReliability);
92  ebuf = (std::string) cfg.value("gfs","estrategy", ebuf);
93  considerOdometryCovariance = cfg.value("gfs","considerOdometryCovariance",considerOdometryCovariance);
94 
95  }
96 
97 
98  CMD_PARSE_BEGIN(1,argc);
99  parseString("-cfg",configfilename); /* to avoid the warning*/
100  parseString("-filename",filename);
101  parseString("-outfilename",outfilename);
102  parseDouble("-xmin",xmin);
103  parseDouble("-xmax",xmax);
104  parseDouble("-ymin",ymin);
105  parseDouble("-ymax",ymax);
106  parseDouble("-delta",delta);
107  parseDouble("-maxrange",maxrange);
108  parseDouble("-maxUrange",maxUrange);
109  parseDouble("-regscore",regscore);
110  parseDouble("-critscore",critscore);
111  parseInt("-kernelSize",kernelSize);
112  parseDouble("-sigma",sigma);
113  parseInt("-iterations",iterations);
114  parseDouble("-lstep",lstep);
115  parseDouble("-astep",astep);
116  parseDouble("-maxMove",maxMove);
117  parseDouble("-srr", srr);
118  parseDouble("-srt", srt);
119  parseDouble("-str", str);
120  parseDouble("-stt", stt);
121  parseInt("-particles",particles);
122  parseDouble("-angularUpdate", angularUpdate);
123  parseDouble("-linearUpdate", linearUpdate);
124  parseDouble("-lsigma", lsigma);
125  parseDouble("-lobsGain", ogain);
126  parseInt("-lskip", lskip);
127  parseInt("-mapUpdate", mapUpdateTime);
128  parseInt("-randseed", randseed);
129  parseFlag("-autosize", autosize);
130  parseFlag("-stdin", readFromStdin);
131  parseDouble("-resampleThreshold", resampleThreshold);
132  parseFlag("-skipMatching", skipMatching);
133  parseFlag("-onLine", onLine);
134  parseFlag("-generateMap", generateMap);
135  parseDouble("-minimumScore", m_minimumScore);
136  parseDouble("-llsamplerange", llsamplerange);
137  parseDouble("-lasamplerange", lasamplerange);
138  parseDouble("-llsamplestep", llsamplestep);
139  parseDouble("-lasamplestep", lasamplestep);
140  parseDouble("-linearOdometryReliability",linearOdometryReliability);
141  parseDouble("-angularOdometryReliability",angularOdometryReliability);
142  parseString("-estrategy", ebuf);
143 
144  parseFlag("-considerOdometryCovariance",considerOdometryCovariance);
146 
147  if (filename.length() <=0){
148  cout << "no filename specified" << endl;
149  return -1;
150  }
151  return 0;
152 }
153 
155  if (onLine){
156  cout << " onLineProcessing" << endl;
157  return 0;
158  }
159  ifstream is;
160  if (fn)
161  is.open(fn);
162  else
163  is.open(filename.c_str());
164  if (! is){
165  cout << "no file found" << endl;
166  return -1;
167  }
168 
169  CarmenConfiguration conf;
170  conf.load(is);
171  is.close();
172 
173  sensorMap=conf.computeSensorMap();
174 
175  if (input)
176  delete input;
177 
178  if (! readFromStdin){
179  plainStream.open(filename.c_str());
180  input=new InputSensorStream(sensorMap, plainStream);
181  cout << "Plain Stream opened="<< (bool) plainStream << endl;
182  } else {
183  input=new InputSensorStream(sensorMap, cin);
184  cout << "Plain Stream opened on stdin" << endl;
185  }
186  return 0;
187 }
188 
190  //This are the processor parameters
191  filename="";
192  outfilename="";
193  xmin=-100.;
194  ymin=-100.;
195  xmax=100.;
196  ymax=100.;
197  delta=0.05;
198 
199  //scan matching parameters
200  sigma=0.05;
201  maxrange=80.;
202  maxUrange=80.;
203  regscore=1e4;
204  lstep=.05;
205  astep=.05;
206  kernelSize=1;
207  iterations=5;
208  critscore=0.;
209  maxMove=1.;
210  lsigma=.075;
211  ogain=3;
212  lskip=0;
213  autosize=false;
214  skipMatching=false;
215 
216  //motion model parameters
217  srr=0.1, srt=0.1, str=0.1, stt=0.1;
218  //particle parameters
219  particles=30;
220  randseed=0;
221 
222  //gfs parameters
223  angularUpdate=0.5;
224  linearUpdate=1;
225  resampleThreshold=0.5;
226 
227  input=0;
228 
229  pthread_mutex_init(&hp_mutex,0);
230  pthread_mutex_init(&ind_mutex,0);
231  pthread_mutex_init(&hist_mutex,0);
232  running=false;
234  mapUpdateTime=5;
235  mapTimer=0;
236  readFromStdin=false;
237  onLine=false;
238  generateMap=false;
239 
240  // This are the dafault settings for a grid map of 5 cm
241  llsamplerange=0.01;
242  llsamplestep=0.01;
243  lasamplerange=0.005;
244  lasamplestep=0.005;
247 
249 /*
250  // This are the dafault settings for a grid map of 10 cm
251  m_llsamplerange=0.1;
252  m_llsamplestep=0.1;
253  m_lasamplerange=0.02;
254  m_lasamplestep=0.01;
255 */
256  // This are the dafault settings for a grid map of 20/25 cm
257 /*
258  m_llsamplerange=0.2;
259  m_llsamplestep=0.1;
260  m_lasamplerange=0.02;
261  m_lasamplestep=0.01;
262  m_generateMap=false;
263 */
264 
265 
266 }
267 
269  pthread_mutex_destroy(&hp_mutex);
270  pthread_mutex_destroy(&ind_mutex);
271  pthread_mutex_destroy(&hist_mutex);
272 
273  for (deque<Event*>::const_iterator it=eventBuffer.begin(); it!=eventBuffer.end(); it++)
274  delete *it;
275 }
276 
277 
279  if (! gpt->input && ! gpt->onLine)
280  return 0;
281 
282 
283  //if started online retrieve the settings from the connection
284 #ifdef CARMEN_SUPPORT
285  if (gpt->onLine){
286  cout << "starting the process:" << endl;
287  CarmenWrapper::initializeIPC(gpt->m_argv[0]);
288  CarmenWrapper::start(gpt->m_argv[0]);
289  cout << "Waiting for retrieving the sensor map:" << endl;
290  while (! CarmenWrapper::sensorMapComputed()){
291  usleep(500000);
292  cout << "." << flush;
293  }
294  gpt->sensorMap=CarmenWrapper::sensorMap();
295  cout << "Connected " << endl;
296  }
297 #else
298  if (gpt->onLine){
299  cout << "FATAL ERROR: cannot run online without the carmen support" << endl;
300  DoneEvent *done=new DoneEvent;
301  gpt->addEvent(done);
302  return 0;
303  }
304 #endif
305 
306  gpt->setSensorMap(gpt->sensorMap);
307  gpt->setMatchingParameters(gpt->maxUrange, gpt->maxrange, gpt->sigma, gpt->kernelSize, gpt->lstep, gpt->astep, gpt->iterations, gpt->lsigma, gpt->ogain, gpt->lskip);
308 
309  double xmin=gpt->xmin,
310  ymin=gpt->ymin,
311  xmax=gpt->xmax,
312  ymax=gpt->ymax;
313 
314  OrientedPoint initialPose(0,0,0);
315 
316  if (gpt->autosize){
317  if (gpt->readFromStdin || gpt->onLine)
318  cout << "Error, cant autosize form stdin" << endl;
319  SensorLog * log=new SensorLog(gpt->sensorMap);
320  ifstream is(gpt->filename.c_str());
321  log->load(is);
322  is.close();
323  initialPose=gpt->boundingBox(log, xmin, ymin, xmax, ymax);
324  delete log;
325  }
326 
327  if( gpt->infoStream()){
328  gpt->infoStream() << " initialPose=" << initialPose.x << " " << initialPose.y << " " << initialPose.theta
329  << cout << " xmin=" << xmin <<" ymin=" << ymin <<" xmax=" << xmax <<" ymax=" << ymax << endl;
330  }
331  gpt->setMotionModelParameters(gpt->srr, gpt->srt, gpt->str, gpt->stt);
333  gpt->setgenerateMap(gpt->generateMap);
334  gpt->GridSlamProcessor::init(gpt->particles, xmin, ymin, xmax, ymax, gpt->delta, initialPose);
335  gpt->setllsamplerange(gpt->llsamplerange);
336  gpt->setllsamplestep(gpt->llsamplestep);
337  gpt->setlasamplerange(gpt->llsamplerange);
338  gpt->setlasamplestep(gpt->llsamplestep);
339 
340 #define printParam(n)\
341  gpt->outputStream() \
342  << "PARAM " << \
343  #n \
344  << " " << gpt->n << endl
345 
346  if (gpt->outfilename.length()>0 ){
347  gpt->outputStream().open(gpt->outfilename.c_str());
350  printParam(xmin);
351  printParam(ymin);
352  printParam(xmax);
353  printParam(ymax);
354  printParam(delta);
355 
356  //scan matching parameters
357  printParam(sigma);
361  printParam(lstep);
362  printParam(astep);
368  printParam(ogain);
369  printParam(lskip);
372 
373  //motion model parameters
374  printParam(srr);
375  printParam(srt);
376  printParam(str);
377  printParam(stt);
378  //particle parameters
381 
382  //gfs parameters
386 
391  }
392  #undef printParam
393 
394  if (gpt->randseed!=0)
395  sampleGaussian(1,gpt->randseed);
396  if (!gpt->infoStream()){
397  cerr << "cant open info stream for writing by unuseful debug messages" << endl;
398  } else {
399  gpt->infoStream() << "setting randseed" << gpt->randseed<< endl;
400  }
401 
402 
403 #ifdef CARMEN_SUPPORT
404  list<RangeReading*> rrlist;
405  if (gpt->onLine){
406  RangeReading rr(0,0);
407  while (1){
408  while (CarmenWrapper::getReading(rr)){
409  RangeReading* nr=new RangeReading(rr);
410  rrlist.push_back(nr);
411  gpt->processScan(*nr);
412  }
413  }
414  }
415 #endif
416  ofstream rawpath("rawpath.dat");
417  if (!gpt->onLine){
418  while(*(gpt->input) && gpt->running){
419  const SensorReading* r;
420  (*(gpt->input)) >> r;
421  if (! r)
422  continue;
423  const RangeReading* rr=dynamic_cast<const RangeReading*>(r);
424  if (rr && gpt->running){
425  const RangeSensor* rs=dynamic_cast<const RangeSensor*>(rr->getSensor());
426  assert (rs && rs->beams().size()==rr->size());
427 
428  bool processed=gpt->processScan(*rr);
429  rawpath << rr->getPose().x << " " << rr->getPose().y << " " << rr->getPose().theta << endl;
430  if (0 && processed){
431  cerr << "Retrieving state .. ";
432  TNodeVector trajetories=gpt->getTrajectories();
433  cerr << "Done" << endl;
434  cerr << "Deleting Tree state .. ";
435  for (TNodeVector::iterator it=trajetories.begin(); it!=trajetories.end(); it++)
436  delete *it;
437  cerr << "Done" << endl;
438  }
439 // if (0 && processed){
440 // cerr << "generating copy" << endl;;
441 // GridSlamProcessor* m_gsp=gpt->clone();
442 // Map<double, DoubleArray2D, false>* pmap=m_gsp->getParticles()[0].map.toDoubleMap() ;
443 // cerr << "deleting" << endl;
444 // delete m_gsp;
445 // delete pmap;
446 // }
447  }
448  const OdometryReading* o=dynamic_cast<const OdometryReading*>(r);
449  if (o && gpt->running){
450  gpt->processTruePos(*o);
451  TruePosEvent* truepos=new TruePosEvent;
452  truepos->pose=o->getPose();
453  }
454  }
455  }
456  rawpath.close();
457 
458  TNodeVector trajetories=gpt->getTrajectories();
459  cerr << "WRITING WEIGHTS" << endl;
460  int pnumber=0;
461  for (TNodeVector::iterator it=trajetories.begin(); it!=trajetories.end(); it++){
462  char buf[10];
463  sprintf(buf, "w-%03d.dat",pnumber);
464  ofstream weightsStream(buf);
466  double oldWeight=0, oldgWeight=0;
467  while (n!=0){
468  double w=n->weight-oldWeight;
469  double gw=n->gweight-oldgWeight;
470  oldWeight=n->weight;
471  oldgWeight=n->gweight;
472  weightsStream << w << " " << gw << endl;
473  n=n->parent;
474  }
475  weightsStream.close();
476  pnumber++;
477  cerr << buf << endl;
478  }
479 
480  DoneEvent *done=new DoneEvent;
481  gpt->addEvent(done);
482  gpt->infoStream() << "Hallo, I am the gsp thread. I have finished. Do you think it is the case of checking for unlocked mutexes." << endl;
483  return 0;
484 }
485 
486 std::vector<OrientedPoint> GridSlamProcessorThread::getHypotheses(){
487  pthread_mutex_lock(&hp_mutex);
488  std::vector<OrientedPoint> retval(hypotheses);
489  pthread_mutex_unlock(&hp_mutex);
490  return retval;
491 }
492 
493 std::vector<unsigned int> GridSlamProcessorThread::getIndexes(){
494  pthread_mutex_lock(&ind_mutex);
495  std::vector<unsigned int> retval(indexes);
496  pthread_mutex_unlock(&ind_mutex);
497  return retval;
498 }
499 
501  if (running)
502  return;
503  running=true;
504  pthread_create(&gfs_thread, 0, (void * (*)(void *))fastslamthread, (void *) this);
505 }
506 
508  if (! running){
509  cout << "PORCO CAZZO" << endl;
510  return;
511  }
512  running=false;
513  void * retval;
514  pthread_join(gfs_thread, &retval);
515 }
516 
518  pthread_mutex_lock(&hp_mutex);
519  hypotheses.clear();
520  weightSums.clear();
521  for (GridSlamProcessor::ParticleVector::const_iterator part=getParticles().begin(); part!=getParticles().end(); part++ ){
522  hypotheses.push_back(part->pose);
523  weightSums.push_back(part->weightSum);
524  }
525 
527  event->scanmatched=false;
528  event->hypotheses=hypotheses;
529  event->weightSums=weightSums;
530  event->neff=m_neff;
531  pthread_mutex_unlock(&hp_mutex);
532 
533  addEvent(event);
534 
536 }
537 
539  pthread_mutex_lock(&ind_mutex);
540  pthread_mutex_lock(&hp_mutex);
541 
542  indexes=GridSlamProcessor::getIndexes();
543 
544  assert (indexes.size()==getParticles().size());
545  ResampleEvent* event=new ResampleEvent;
546  event->indexes=indexes;
547 
548  pthread_mutex_unlock(&hp_mutex);
549  pthread_mutex_unlock(&ind_mutex);
550 
551  addEvent(event);
552 
554 }
555 
557  pthread_mutex_lock(&hp_mutex);
558  hypotheses.clear();
559  weightSums.clear();
560  unsigned int bestIdx=0;
561  double bestWeight=-1e1000;
562  unsigned int idx=0;
563  for (GridSlamProcessor::ParticleVector::const_iterator part=getParticles().begin(); part!=getParticles().end(); part++ ){
564  hypotheses.push_back(part->pose);
565  weightSums.push_back(part->weightSum);
566  if(part->weightSum>bestWeight){
567  bestIdx=idx;
568  bestWeight=part->weightSum;
569  }
570  idx++;
571  }
572 
574  event->scanmatched=true;
575  event->hypotheses=hypotheses;
576  event->weightSums=weightSums;
577  event->neff=m_neff;
578  addEvent(event);
579 
580  if (! mapTimer){
581  MapEvent* event=new MapEvent;
582  event->index=bestIdx;
583  event->pmap=new ScanMatcherMap(getParticles()[bestIdx].map);
584  event->pose=getParticles()[bestIdx].pose;
585  addEvent(event);
586  }
587 
588  mapTimer++;
590 
591  pthread_mutex_unlock(&hp_mutex);
592 
594 }
595 
597 }
598 
600 }
601 
603 }
604 
606  pthread_mutex_lock(&hist_mutex);
607  while (eventBuffer.size()>eventBufferLength){
608  Event* event=eventBuffer.front();
609  delete event;
610  eventBuffer.pop_front();
611  }
612  eventBuffer.push_back(e);
613  pthread_mutex_unlock(&hist_mutex);
614 }
615 
617  pthread_mutex_lock(&hist_mutex);
618  EventDeque copy(eventBuffer);
619  eventBuffer.clear();
620  pthread_mutex_unlock(&hist_mutex);
621  return copy;
622 }
623 
625 
627  if (pmap)
628  delete pmap;
629 }
630 
632  eventBufferLength=length;
633 }
634 
635 OrientedPoint GridSlamProcessorThread::boundingBox(SensorLog* log, double& xmin, double& ymin, double& xmax, double& ymax) const{
636  OrientedPoint initialPose(0,0,0);
637  initialPose=log->boundingBox(xmin, ymin, xmax, ymax);
638  xmin-=3*maxrange;
639  ymin-=3*maxrange;
640  xmax+=3*maxrange;
641  ymax+=3*maxrange;
642  return initialPose;
643 }
const char *const *argv double delta
Definition: gfs2stream.cpp:19
int init(int argc, const char *const *argv)
Definition: gsp_thread.cpp:37
InputSensorStream * input
Definition: gsp_thread.h:164
virtual void onResampleUpdate()
Definition: gsp_thread.cpp:538
virtual void onOdometryUpdate()
Definition: gsp_thread.cpp:517
const ParticleVector & getParticles() const
#define parseFlag(name, value)
Definition: commandline.h:28
std::vector< GridSlamProcessor::TNode * > TNodeVector
unsigned int mapTimer
Definition: gsp_thread.h:107
const Sensor * getSensor() const
Definition: sensorreading.h:13
static void * fastslamthread(GridSlamProcessorThread *gpt)
Definition: gsp_thread.cpp:278
int loadFiles(const char *fn=0)
Definition: gsp_thread.cpp:154
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)
std::vector< double > weightSums
Definition: gsp_thread.h:112
double sampleGaussian(double sigma, unsigned int S=0)
Definition: stat.cpp:49
pthread_mutex_t hist_mutex
Definition: gsp_thread.h:113
OrientedPoint boundingBox(double &xmin, double &ymin, double &xmax, double &ymax) const
Definition: sensorlog.cpp:121
bool processScan(const RangeReading &reading, int adaptParticles=0)
virtual void syncResampleUpdate()
Definition: gsp_thread.cpp:599
virtual SensorMap computeSensorMap() const
const char *const * m_argv
Definition: gsp_thread.h:173
virtual std::istream & load(std::istream &is)
CMD_PARSE_END
Definition: gfs2stream.cpp:32
#define parseDouble(name, value)
Definition: commandline.h:44
#define CMD_PARSE_BEGIN_SILENT(i, count)
Definition: commandline.h:73
#define printParam(n)
const OrientedPoint & getPose() const
Definition: rangereading.h:15
#define parseInt(name, value)
Definition: commandline.h:52
double maxrange
Definition: gfs2stream.cpp:22
void addEvent(Event *)
Definition: gsp_thread.cpp:605
std::string outfilename
Definition: gsp_thread.h:119
OrientedPoint boundingBox(SensorLog *log, double &xmin, double &ymin, double &xmax, double &ymax) const
Definition: gsp_thread.cpp:635
std::vector< unsigned int > indexes
Definition: gsp_thread.h:111
std::istream & load(std::istream &is)
Definition: sensorlog.cpp:23
void setUpdateDistances(double linear, double angular, double resampleThreshold)
void setSensorMap(const SensorMap &smap)
void processTruePos(const OdometryReading &odometry)
deque< Event * > EventDeque
Definition: gsp_thread.h:73
virtual void syncOdometryUpdate()
Definition: gsp_thread.cpp:596
#define parseString(name, value)
Definition: commandline.h:35
double linearOdometryReliability
Definition: gsp_thread.h:147
#define CMD_PARSE_END_SILENT
Definition: commandline.h:79
std::vector< unsigned int > getIndexes()
Definition: gsp_thread.cpp:493
bool part
Definition: gfs2stream.cpp:40
std::vector< OrientedPoint > getHypotheses()
Definition: gsp_thread.cpp:486
unsigned int eventBufferLength
Definition: gsp_thread.h:105
#define parseStringSilent(name, value)
Definition: commandline.h:91
Map< PointAccumulator, HierarchicalArray2D< PointAccumulator > > ScanMatcherMap
Definition: smmap.h:50
std::vector< OrientedPoint > hypotheses
Definition: gsp_thread.h:110
double angularOdometryReliability
Definition: gsp_thread.h:148
std::vector< unsigned int > indexes
Definition: gsp_thread.h:60
unsigned int mapUpdateTime
Definition: gsp_thread.h:106
pthread_mutex_t hp_mutex
Definition: gsp_thread.h:113
ifstream is(argv[c])
void setEventBufferSize(unsigned int length)
Definition: gsp_thread.cpp:631
#define n
Definition: eig3.cpp:11
void setMotionModelParameters(double srr, double srt, double str, double stt)
const OrientedPoint & getPose() const
virtual void onScanmatchUpdate()
Definition: gsp_thread.cpp:556
pthread_mutex_t ind_mutex
Definition: gsp_thread.h:113
const std::vector< Beam > & beams() const
Definition: rangesensor.h:23
virtual void syncScanmatchUpdate()
Definition: gsp_thread.cpp:602
CMD_PARSE_BEGIN(1, argc-2)
unsigned int randseed
Definition: gsp_thread.h:170


openslam_gmapping
Author(s): Giorgio Grisetti, Cyrill Stachniss, Wolfram Burgard
autogenerated on Mon Jun 10 2019 14:04:22