24 m_resampleThreshold=0.5;
33 m_obsSigmaGain=gsp.m_obsSigmaGain;
34 m_resampleThreshold=gsp.m_resampleThreshold;
35 m_minimumScore=gsp.m_minimumScore;
40 m_resampleThreshold=gsp.m_resampleThreshold;
52 cerr <<
"FILTER COPY CONSTRUCTOR" << endl;
65 m_regScore=gsp.m_regScore;
66 m_critScore=gsp.m_critScore;
67 m_maxMove=gsp.m_maxMove;
69 m_linearThresholdDistance=gsp.m_linearThresholdDistance;
70 m_angularThresholdDistance=gsp.m_angularThresholdDistance;
71 m_obsSigmaGain=gsp.m_obsSigmaGain;
73 #ifdef MAP_CONSISTENCY_CHECK 74 cerr << __PRETTY_FUNCTION__ <<
": trajectories copy.... ";
77 for (
unsigned int i=0; i<v.size(); i++){
80 #ifdef MAP_CONSISTENCY_CHECK 81 cerr <<
"end" << endl;
85 cerr <<
"Tree: normalizing, resetting and propagating weights within copy construction/cloneing ..." ;
87 cerr <<
".done!" <<endl;
93 m_resampleThreshold=0.5;
99 # ifdef MAP_CONSISTENCY_CHECK 100 cerr << __PRETTY_FUNCTION__ <<
": performing preclone_fit_test" << endl;
101 typedef std::map<autoptr< Array2D<PointAccumulator> >::reference*
const,
int> PointerMap;
106 for (
int x=0; x<h1.getXSize(); x++){
107 for (
int y=0; y<h1.getYSize(); y++){
119 cerr << __PRETTY_FUNCTION__ <<
": Number of allocated chunks" << pmap.size() << endl;
120 for(PointerMap::const_iterator it=pmap.begin(); it!=pmap.end(); it++)
121 assert(it->first->shares==(
unsigned int)it->second);
123 cerr << __PRETTY_FUNCTION__ <<
": SUCCESS, the error is somewhere else" << endl;
127 # ifdef MAP_CONSISTENCY_CHECK 128 cerr << __PRETTY_FUNCTION__ <<
": trajectories end" << endl;
129 cerr << __PRETTY_FUNCTION__ <<
": performing afterclone_fit_test" << endl;
130 ParticleVector::const_iterator jt=cloned->
m_particles.begin();
137 for (
int x=0; x<h1.getXSize(); x++){
138 for (
int y=0; y<h1.getYSize(); y++){
146 cerr << __PRETTY_FUNCTION__ <<
": SUCCESS, the error is somewhere else" << endl;
152 cerr << __PRETTY_FUNCTION__ <<
": Start" << endl;
153 cerr << __PRETTY_FUNCTION__ <<
": Deleting tree" << endl;
155 #ifdef TREE_CONSISTENCY_CHECK 156 TNode* node=it->node;
166 # ifdef MAP_CONSISTENCY_CHECK 167 cerr << __PRETTY_FUNCTION__ <<
": performing predestruction_fit_test" << endl;
168 typedef std::map<autoptr< Array2D<PointAccumulator> >::reference*
const,
int> PointerMap;
173 for (
int x=0; x<h1.getXSize(); x++){
174 for (
int y=0; y<h1.getYSize(); y++){
186 cerr << __PRETTY_FUNCTION__ <<
": Number of allocated chunks" << pmap.size() << endl;
187 for(PointerMap::const_iterator it=pmap.begin(); it!=pmap.end(); it++)
188 assert(it->first->shares>=(
unsigned int)it->second);
189 cerr << __PRETTY_FUNCTION__ <<
": SUCCESS, the error is somewhere else" << endl;
196 int iterations,
double likelihoodSigma,
double likelihoodGain,
unsigned int likelihoodSkip){
197 m_obsSigmaGain=likelihoodGain;
201 <<
" -maxUrange "<< range
202 <<
" -sigma "<< sigma
203 <<
" -kernelSize "<< kernsize
204 <<
" -lstep " << lopt
205 <<
" -lobsGain " << m_obsSigmaGain
206 <<
" -astep " << aopt << endl;
212 (
double srr,
double srt,
double str,
double stt){
220 <<
" -str "<< str <<
" -stt "<< stt << endl;
225 m_linearThresholdDistance=linear;
226 m_angularThresholdDistance=angular;
227 m_resampleThreshold=resampleThreshold;
230 <<
" -angularUpdate "<< angular
231 <<
" -resampleThreshold " << m_resampleThreshold << endl;
237 map(m), pose(0,0,0), weight(0), weightSum(0), gweight(0), previousIndex(0){
250 SensorMap::const_iterator laser_it=smap.find(std::string(
"FLASER"));
251 if (laser_it==smap.end()){
252 cerr <<
"Attempting to load the new carmen log format" << endl;
253 laser_it=smap.find(std::string(
"ROBOTLASER1"));
254 assert(laser_it!=smap.end());
257 assert(rangeSensor && rangeSensor->beams().size());
259 m_beams=
static_cast<unsigned int>(rangeSensor->beams().size());
260 double* angles=
new double[rangeSensor->beams().size()];
261 for (
unsigned int i=0; i<
m_beams; i++){
262 angles[i]=rangeSensor->beams()[i].pose.theta;
276 <<
" -xmin "<< m_xmin
277 <<
" -xmax "<< m_xmax
278 <<
" -ymin "<< m_ymin
279 <<
" -ymax "<< m_ymax
280 <<
" -delta "<< m_delta
281 <<
" -particles "<< size << endl;
287 for (
unsigned int i=0; i<size; i++){
344 m_outputStream << setiosflags(ios::fixed) << setprecision(3) << pose.
x <<
" " << pose.
y <<
" ";
363 cerr <<
"***********************************************************************" << endl;
364 cerr <<
"********** Error: m_distanceThresholdCheck overridden!!!! *************" << endl;
365 cerr <<
"m_distanceThresholdCheck=" << m_distanceThresholdCheck << endl;
366 cerr <<
"Old Odometry Pose= " << m_odoPose.x <<
" " << m_odoPose.y
367 <<
" " <<m_odoPose.theta << endl;
368 cerr <<
"New Odometry Pose (reported from observation)= " << relPose.
x <<
" " << relPose.
y 369 <<
" " <<relPose.
theta << endl;
370 cerr <<
"***********************************************************************" << endl;
371 cerr <<
"** The Odometry has a big jump here. This is probably a bug in the **" << endl;
372 cerr <<
"** odometry/laser input. We continue now, but the result is probably **" << endl;
373 cerr <<
"** crap or can lead to a core dump since the map doesn't fit.... C&G **" << endl;
374 cerr <<
"***********************************************************************" << endl;
379 bool processed=
false;
405 assert(reading.size()==
m_beams);
406 double * plainReading =
new double[
m_beams];
407 for(
unsigned int i=0; i<
m_beams; i++){
408 plainReading[i]=reading[i];
415 static_cast<const RangeSensor*>(reading.
getSensor()),
423 for (RangeReading::const_iterator b=reading.begin(); b!=reading.end(); b++){
432 m_outputStream << setiosflags(ios::fixed) << setprecision(3) << pose.
x <<
" " << pose.
y <<
" ";
448 resample(plainReading, adaptParticles, reading_copy);
469 delete [] plainReading;
478 it->previousPose=it->pose;
const char *const *argv double delta
double registerScan(ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
std::ofstream & outputStream()
virtual void onScanmatchUpdate()
const RangeReading * reading
std::vector< GridSlamProcessor::TNode * > TNodeVector
Particle(const ScanMatcherMap &map)
const Sensor * getSensor() const
std::vector< unsigned int > m_indexes
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)
bool processScan(const RangeReading &reading, int adaptParticles=0)
bool resample(const double *plainReading, int adaptParticles, const RangeReading *rr=0)
virtual ~GridSlamProcessor()
virtual void onOdometryUpdate()
const OrientedPoint & getPose() const
void setLaserParameters(unsigned int beams, double *angles, const OrientedPoint &lpose)
ParticleVector m_particles
void setUpdateDistances(double linear, double angular, double resampleThreshold)
void invalidateActiveArea()
void setSensorMap(const SensorMap &smap)
void processTruePos(const OdometryReading &odometry)
GridSlamProcessor * clone() const
OrientedPoint m_lastPartPose
std::ofstream m_outputStream
OrientedPoint drawFromMotion(const OrientedPoint &p, double linearMove, double angularMove) const
void scanMatch(const double *plainReading)
virtual void onResampleUpdate()
MotionModel m_motionModel
std::map< std::string, Sensor * > SensorMap
void setMatchingParameters(double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations, double likelihoodSigma=1, unsigned int likelihoodSkip=0)
TNodeVector getTrajectories() const
std::ostream & m_infoStream
void init(unsigned int size, double xmin, double ymin, double xmax, double ymax, double delta, OrientedPoint initialPose=OrientedPoint(0, 0, 0))
double max(double a, double b)
void setMotionModelParameters(double srr, double srt, double str, double stt)
void computeActiveArea(ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
const double m_distanceThresholdCheck
const OrientedPoint & getPose() const
int getBestParticleIndex() const
void updateTreeWeights(bool weightsAlreadyNormalized=false)