gfs-carmen.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 3-Clause BSD License
9  * and is copyrighted by Giorgio Grisetti, Cyrill Stachniss,
10  * and Wolfram Burgard.
11  *
12  * Further information on this license can be found at:
13  * https://opensource.org/licenses/BSD-3-Clause
14  *
15  * GMAPPING is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied
17  * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
18  * PURPOSE.
19  *
20  *****************************************************************/
21 
22 
28 
29 #define DEBUG cout << __func__
30 
31 /*
32 Example file for interfacing carmen, and gfs.
33 
34 if you want to look for a specific topic search for one of the following keywords in the file comments
35 
36 KEYWORDS:
37  CREATION
38  INITIALIZATION
39  SENSOR MAP
40  BEST PARTICLE INDEX
41  PARTICLE VECTOR
42  PARTICLE TRAJECTORIES
43  BEST MAP
44  BOUNDING BOX
45 */
46 
47 using namespace GMapping;
48 using namespace std;
49 
50 int main(int argc, const char * const * argv){
51 
52  std::string outfilename="";
53  double xmin=-100.;
54  double ymin=-100.;
55  double xmax=100.;
56  double ymax=100.;
57  double delta=0.05;
58 
59  //scan matching parameters
60  double sigma=0.05;
61  double maxrange=80.;
62  double maxUrange=80.;
63  double regscore=1e4;
64  double lstep=.05;
65  double astep=.05;
66  int kernelSize=1;
67  int iterations=5;
68  double critscore=0.;
69  double maxMove=1.;
70  double lsigma=.075;
71  double ogain=3;
72  int lskip=0;
73 
74  //motion model parameters
75  double srr=0.01, srt=0.01, str=0.01, stt=0.01;
76  //particle parameters
77  int particles=30;
78 
79 
80  //gfs parameters
81  double angularUpdate=0.5;
82  double linearUpdate=1;
83  double resampleThreshold=0.5;
84  bool generateMap=true;
85 
86  std::string configfilename = "";
87 
88  CMD_PARSE_BEGIN_SILENT(1,argc);
89  parseStringSilent("-cfg",configfilename);
91 
92  if (configfilename.length()>0){
93  ConfigFile cfg(configfilename);
94  outfilename = (std::string) cfg.value("gfs","outfilename",outfilename);
95  xmin = cfg.value("gfs","xmin", xmin);
96  xmax = cfg.value("gfs","xmax",xmax);
97  ymin = cfg.value("gfs","ymin",ymin);
98  ymax = cfg.value("gfs","ymax",ymax);
99  delta = cfg.value("gfs","delta",delta);
100  maxrange = cfg.value("gfs","maxrange",maxrange);
101  maxUrange = cfg.value("gfs","maxUrange",maxUrange);
102  regscore = cfg.value("gfs","regscore",regscore);
103  critscore = cfg.value("gfs","critscore",critscore);
104  kernelSize = cfg.value("gfs","kernelSize",kernelSize);
105  sigma = cfg.value("gfs","sigma",sigma);
106  iterations = cfg.value("gfs","iterations",iterations);
107  lstep = cfg.value("gfs","lstep",lstep);
108  astep = cfg.value("gfs","astep",astep);
109  maxMove = cfg.value("gfs","maxMove",maxMove);
110  srr = cfg.value("gfs","srr", srr);
111  srt = cfg.value("gfs","srt", srt);
112  str = cfg.value("gfs","str", str);
113  stt = cfg.value("gfs","stt", stt);
114  particles = cfg.value("gfs","particles",particles);
115  angularUpdate = cfg.value("gfs","angularUpdate", angularUpdate);
116  linearUpdate = cfg.value("gfs","linearUpdate", linearUpdate);
117  lsigma = cfg.value("gfs","lsigma", lsigma);
118  ogain = cfg.value("gfs","lobsGain", ogain);
119  lskip = (int)cfg.value("gfs","lskip", lskip);
120  // randseed = cfg.value("gfs","randseed", randseed);
121  resampleThreshold = cfg.value("gfs","resampleThreshold", resampleThreshold);
122  generateMap = cfg.value("gfs","generateMap", generateMap);
123  }
124 
125 
126  CMD_PARSE_BEGIN(1,argc);
127  parseString("-cfg",configfilename);
128  parseString("-outfilename",outfilename);
129  parseDouble("-xmin",xmin);
130  parseDouble("-xmax",xmax);
131  parseDouble("-ymin",ymin);
132  parseDouble("-ymax",ymax);
133  parseDouble("-delta",delta);
134  parseDouble("-maxrange",maxrange);
135  parseDouble("-maxUrange",maxUrange);
136  parseDouble("-regscore",regscore);
137  parseDouble("-critscore",critscore);
138  parseInt("-kernelSize",kernelSize);
139  parseDouble("-sigma",sigma);
140  parseInt("-iterations",iterations);
141  parseDouble("-lstep",lstep);
142  parseDouble("-astep",astep);
143  parseDouble("-maxMove",maxMove);
144  parseDouble("-srr", srr);
145  parseDouble("-srt", srt);
146  parseDouble("-str", str);
147  parseDouble("-stt", stt);
148  parseInt("-particles",particles);
149  parseDouble("-angularUpdate", angularUpdate);
150  parseDouble("-linearUpdate", linearUpdate);
151  parseDouble("-lsigma", lsigma);
152  parseDouble("-lobsGain", ogain);
153  parseInt("-lskip", lskip);
154  parseDouble("-resampleThreshold", resampleThreshold);
155  parseFlag("-generateMap", generateMap);
157 
158  cerr << "Parameter parsed, connecting to Carmen!";
159 
161  CarmenWrapper::start(argv[0]);
162 
164  usleep(500000);
165  cerr << "." << flush;
166  }
167 
168  //CREATION
169 
170  GridSlamProcessor* processor=new GridSlamProcessor;
171 
172  //SENSOR MAP
173  //loads from the carmen wrapper the laser and robot settings
175  cerr << "Connected " << endl;
176  processor->setSensorMap(sensorMap);
177 
178  //set the command line parameters
179  processor->setMatchingParameters(maxUrange, maxrange, sigma, kernelSize, lstep, astep, iterations, lsigma, ogain, lskip);
180  processor->setMotionModelParameters(srr, srt, str, stt);
181  processor->setUpdateDistances(linearUpdate, angularUpdate, resampleThreshold);
182  processor->setgenerateMap(generateMap);
183  OrientedPoint initialPose(xmin+xmax/2, ymin+ymax/2, 0);
184 
185 
186  //INITIALIZATION
187  processor->init(particles, xmin, ymin, xmax, ymax, delta, initialPose);
188  if (outfilename.length()>0)
189  processor->outputStream().open(outfilename.c_str());
190 
191  bool running=true;
192 
193  GridSlamProcessor* ap, *copy=processor->clone();
194  ap=processor; processor=copy; copy=ap;
195 
196  //this is the CORE LOOP;
197  RangeReading rr(0,0);
198  while (running){
199  while (CarmenWrapper::getReading(rr)){
200 
201 
202  bool processed=processor->processScan(rr);
203 
204  //this returns true when the algorithm effectively processes (the traveled path since the last processing is over a given threshold)
205  if (processed){
206  cerr << "PROCESSED" << endl;
207  //for searching for the BEST PARTICLE INDEX
208  // unsigned int best_idx=processor->getBestParticleIndex();
209 
210  //if you want to access to the PARTICLE VECTOR
211  const GridSlamProcessor::ParticleVector& particles = processor->getParticles();
212  //remember to use a const reference, otherwise it copys the whole particles and maps
213 
214  //this is for recovering the tree of PARTICLE TRAJECTORIES (obtaining the ancestor of each particle)
215  cerr << "Particle reproduction story begin" << endl;
216  for (unsigned int i=0; i<particles.size(); i++){
217  cerr << particles[i].previousIndex << "->" << i << " ";
218  }
219  cerr << "Particle reproduction story end" << endl;
220 /*
221  //then if you want to access the BEST MAP,
222  //of course by copying it in a plain structure
223  Map<double, DoubleArray2D, false>* mymap = processor->getParticles()[best_idx].map.toDoubleMap();
224  //at this point mymap is yours. Can do what you want.
225 
226  double best_weight=particles[best_idx].weightSum;
227  cerr << "Best Particle is " << best_idx << " with weight " << best_weight << endl;
228 
229 */
230  cerr << __func__ << "CLONING... " << endl;
231  GridSlamProcessor* newProcessor=processor->clone();
232  cerr << "DONE" << endl;
233  cerr << __func__ << "DELETING... " << endl;
234  delete processor;
235  cerr << "DONE" << endl;
236  processor=newProcessor;
237  }
238  }
239  }
240  return 0;
241 }
242 
GMapping::SensorMap
std::map< std::string, Sensor * > SensorMap
Definition: sensor.h:20
GMapping::ConfigFile
Definition: configfile.h:85
GMapping::CarmenWrapper::sensorMapComputed
static bool sensorMapComputed()
Definition: carmenwrapper.cpp:144
CMD_PARSE_BEGIN_SILENT
#define CMD_PARSE_BEGIN_SILENT(i, count)
Definition: commandline.h:72
parseString
#define parseString(name, value)
Definition: commandline.h:34
GMapping::CarmenWrapper::initializeIPC
static void initializeIPC(const char *name)
Definition: carmenwrapper.cpp:42
GMapping::GridSlamProcessor::setMatchingParameters
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)
Definition: gridslamprocessor.cpp:195
GMapping::GridSlamProcessor::ParticleVector
std::vector< Particle > ParticleVector
Definition: gridslamprocessor.h:127
GMapping::main
int main(int argc, conat char **argv)
Definition: lumiles.h:45
parseInt
#define parseInt(name, value)
Definition: commandline.h:51
GMapping
Definition: configfile.cpp:34
GMapping::GridSlamProcessor::outputStream
std::ofstream & outputStream()
Definition: gridslamprocessor.cpp:489
GMapping::GridSlamProcessor::processScan
bool processScan(const RangeReading &reading, int adaptParticles=0)
Definition: gridslamprocessor.cpp:316
parseDouble
#define parseDouble(name, value)
Definition: commandline.h:43
GMapping::CarmenWrapper::sensorMap
static const SensorMap & sensorMap()
Definition: carmenwrapper.cpp:151
delta
const char *const *argv double delta
Definition: gfs2stream.cpp:19
CMD_PARSE_END_SILENT
#define CMD_PARSE_END_SILENT
Definition: commandline.h:78
commandline.h
CMD_PARSE_BEGIN
CMD_PARSE_BEGIN(1, argc-2)
GMapping::GridSlamProcessor::clone
GridSlamProcessor * clone() const
Definition: gridslamprocessor.cpp:98
GMapping::GridSlamProcessor
Definition: gridslamprocessor.h:35
GMapping::GridSlamProcessor::setUpdateDistances
void setUpdateDistances(double linear, double angular, double resampleThreshold)
Definition: gridslamprocessor.cpp:224
parseFlag
#define parseFlag(name, value)
Definition: commandline.h:27
GMapping::GridSlamProcessor::getParticles
const ParticleVector & getParticles() const
Definition: gridslamprocessor.h:173
GMapping::ConfigFile::value
const AutoVal & value(const std::string &section, const std::string &entry) const
Definition: configfile.cpp:227
GMapping::GridSlamProcessor::setSensorMap
void setSensorMap(const SensorMap &smap)
Definition: gridslamprocessor.cpp:242
GMapping::RangeReading
Definition: rangereading.h:17
GMapping::GridSlamProcessor::init
void init(unsigned int size, double xmin, double ymin, double xmax, double ymax, double delta, OrientedPoint initialPose=OrientedPoint(0, 0, 0))
Definition: gridslamprocessor.cpp:268
GMapping::CarmenWrapper::start
static bool start(const char *name)
Definition: carmenwrapper.cpp:103
GMapping::CarmenWrapper::getReading
static bool getReading(RangeReading &reading)
Definition: carmenwrapper.cpp:175
GMapping::GridSlamProcessor::setMotionModelParameters
void setMotionModelParameters(double srr, double srt, double str, double stt)
Definition: gridslamprocessor.cpp:212
orientedboundingbox.h
CMD_PARSE_END
CMD_PARSE_END
Definition: gfs2stream.cpp:32
gridslamprocessor.h
parseStringSilent
#define parseStringSilent(name, value)
Definition: commandline.h:90
GMapping::orientedpoint< double, double >
maxrange
double maxrange
Definition: gfs2stream.cpp:22
configfile.h
carmenwrapper.h


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