27 #include <configfile/configfile.h> 33 #define DEBUG cout << __PRETTY_FUNCTION__ 40 std::string configfilename;
41 std::string ebuf=
"not_set";
47 if (configfilename.length()>0){
48 ConfigFile cfg(configfilename);
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);
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);
127 parseInt(
"-mapUpdate", mapUpdateTime);
131 parseDouble(
"-resampleThreshold", resampleThreshold);
132 parseFlag(
"-skipMatching", skipMatching);
140 parseDouble(
"-linearOdometryReliability",linearOdometryReliability);
141 parseDouble(
"-angularOdometryReliability",angularOdometryReliability);
144 parseFlag(
"-considerOdometryCovariance",considerOdometryCovariance);
147 if (filename.length() <=0){
148 cout <<
"no filename specified" << endl;
156 cout <<
" onLineProcessing" << endl;
163 is.open(filename.c_str());
165 cout <<
"no file found" << endl;
178 if (! readFromStdin){
179 plainStream.open(filename.c_str());
181 cout <<
"Plain Stream opened="<< (bool) plainStream << endl;
184 cout <<
"Plain Stream opened on stdin" << endl;
284 #ifdef CARMEN_SUPPORT 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()){
292 cout <<
"." << flush;
294 gpt->
sensorMap=CarmenWrapper::sensorMap();
295 cout <<
"Connected " << endl;
299 cout <<
"FATAL ERROR: cannot run online without the carmen support" << endl;
318 cout <<
"Error, cant autosize form stdin" << endl;
328 gpt->
infoStream() <<
" initialPose=" << initialPose.
x <<
" " << initialPose.
y <<
" " << initialPose.
theta 329 << cout <<
" xmin=" << xmin <<
" ymin=" <<
ymin <<
" xmax=" <<
xmax <<
" ymax=" <<
ymax << endl;
340 #define printParam(n)\ 341 gpt->outputStream() \ 344 << " " << gpt->n << endl 397 cerr <<
"cant open info stream for writing by unuseful debug messages" << endl;
403 #ifdef CARMEN_SUPPORT 404 list<RangeReading*> rrlist;
408 while (CarmenWrapper::getReading(rr)){
410 rrlist.push_back(nr);
416 ofstream rawpath(
"rawpath.dat");
420 (*(gpt->
input)) >> r;
426 assert (rs && rs->
beams().size()==rr->size());
431 cerr <<
"Retrieving state .. ";
433 cerr <<
"Done" << endl;
434 cerr <<
"Deleting Tree state .. ";
435 for (TNodeVector::iterator it=trajetories.begin(); it!=trajetories.end(); it++)
437 cerr <<
"Done" << endl;
459 cerr <<
"WRITING WEIGHTS" << endl;
461 for (TNodeVector::iterator it=trajetories.begin(); it!=trajetories.end(); it++){
463 sprintf(buf,
"w-%03d.dat",pnumber);
464 ofstream weightsStream(buf);
466 double oldWeight=0, oldgWeight=0;
468 double w=n->
weight-oldWeight;
469 double gw=n->
gweight-oldgWeight;
472 weightsStream << w <<
" " << gw << endl;
475 weightsStream.close();
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;
488 std::vector<OrientedPoint> retval(
hypotheses);
495 std::vector<unsigned int> retval(
indexes);
509 cout <<
"PORCO CAZZO" << endl;
542 indexes=GridSlamProcessor::getIndexes();
560 unsigned int bestIdx=0;
561 double bestWeight=-1e1000;
566 if(
part->weightSum>bestWeight){
568 bestWeight=
part->weightSum;
582 event->
index=bestIdx;
637 initialPose=log->
boundingBox(xmin, ymin, xmax, ymax);
const char *const *argv double delta
int init(int argc, const char *const *argv)
InputSensorStream * input
std::ofstream & outputStream()
virtual void onResampleUpdate()
virtual void onOdometryUpdate()
const ParticleVector & getParticles() const
#define parseFlag(name, value)
std::vector< GridSlamProcessor::TNode * > TNodeVector
const Sensor * getSensor() const
static void * fastslamthread(GridSlamProcessorThread *gpt)
int loadFiles(const char *fn=0)
std::ostream & infoStream()
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
double sampleGaussian(double sigma, unsigned int S=0)
pthread_mutex_t hist_mutex
OrientedPoint boundingBox(double &xmin, double &ymin, double &xmax, double &ymax) const
bool processScan(const RangeReading &reading, int adaptParticles=0)
virtual void syncResampleUpdate()
virtual SensorMap computeSensorMap() const
const char *const * m_argv
GridSlamProcessorThread()
virtual std::istream & load(std::istream &is)
#define parseDouble(name, value)
#define CMD_PARSE_BEGIN_SILENT(i, count)
bool considerOdometryCovariance
const OrientedPoint & getPose() const
#define parseInt(name, value)
OrientedPoint boundingBox(SensorLog *log, double &xmin, double &ymin, double &xmax, double &ymax) const
std::vector< unsigned int > indexes
std::istream & load(std::istream &is)
void setUpdateDistances(double linear, double angular, double resampleThreshold)
void setSensorMap(const SensorMap &smap)
void processTruePos(const OdometryReading &odometry)
deque< Event * > EventDeque
virtual void syncOdometryUpdate()
#define parseString(name, value)
double linearOdometryReliability
#define CMD_PARSE_END_SILENT
~GridSlamProcessorThread()
std::vector< unsigned int > getIndexes()
std::vector< OrientedPoint > getHypotheses()
unsigned int eventBufferLength
#define parseStringSilent(name, value)
Map< PointAccumulator, HierarchicalArray2D< PointAccumulator > > ScanMatcherMap
std::vector< OrientedPoint > hypotheses
double angularOdometryReliability
TNodeVector getTrajectories() const
std::vector< unsigned int > indexes
unsigned int mapUpdateTime
void setEventBufferSize(unsigned int length)
void setMotionModelParameters(double srr, double srt, double str, double stt)
const OrientedPoint & getPose() const
virtual void onScanmatchUpdate()
pthread_mutex_t ind_mutex
const std::vector< Beam > & beams() const
virtual void syncScanmatchUpdate()
CMD_PARSE_BEGIN(1, argc-2)