11 : m_map(m.getCenter(), m.getWorldSizeX(), m.getWorldSizeY(), m.getResolution()),
24 (
double xmin,
double ymin,
double xmax,
double ymax,
double delta,
double patchdelta):
25 m_map(
Point((xmax+xmin)*.5, (ymax+ymin)*.5), xmax-xmin, ymax-ymin, patchdelta),
m_pose(0,0,0){
49 SensorMap::const_iterator laser_it=
m_sensorMap.find(sensorName);
52 assert(rangeSensor && rangeSensor->beams().size());
54 m_beams=
static_cast<unsigned int>(rangeSensor->beams().size());
55 double* angles=
new double[rangeSensor->beams().size()];
56 for (
unsigned int i=0; i<
m_beams; i++){
57 angles[i]=rangeSensor->beams()[i].pose.theta;
86 double lin_move=move*move;
88 cerr <<
"Too big jump in the log file: " << lin_move << endl;
89 cerr <<
"relPose=" << relPose.
x <<
" " <<relPose.
y << endl;
90 cerr <<
"ignoring" << endl;
94 move.x=move.y=move.theta=0;
97 double s=sin(dth),
c=cos(dth);
99 dPose.
x=
c*move.x-s*move.y;
100 dPose.
y=s*move.x+
c*move.y;
101 dPose.
theta=move.theta;
103 #ifdef SCANMATHCERPROCESSOR_DEBUG 104 cout <<
"abs-move x="<< dPose.
x <<
" y=" << dPose.
y <<
" theta=" << dPose.
theta << endl;
109 #ifdef SCANMATHCERPROCESSOR_DEBUG 110 cout <<
"StartPose: x=" 120 assert(reading.size()==
m_beams);
133 double * plainReading =
new double[
m_beams];
137 #ifdef SCANMATHCERPROCESSOR_DEBUG 170 #ifdef SCANMATHCERPROCESSOR_DEBUG 172 cout <<
"evals=" << eval[0] <<
" " << eval[1]<<
" " << eval[2]<<endl;
179 cerr <<
"USING ICP" << endl;
189 #ifdef SCANMATHCERPROCESSOR_DEBUG 190 cout <<
"Registering" << endl;
194 #ifdef SCANMATHCERPROCESSOR_DEBUG 195 cout <<
"New Scan added, using odo pose" << endl;
200 #ifdef SCANMATHCERPROCESSOR_DEBUG 201 cout <<
"New Scan added, using matched pose" << endl;
206 #ifdef SCANMATHCERPROCESSOR_DEBUG 207 cout <<
" FinalPose: x=" 208 << newPose.
x <<
" y=" << newPose.
y <<
" theta=" << newPose.
theta << endl;
209 cout <<
"score=" << score << endl;
212 delete [] plainReading;
217 (
double urange,
double range,
double sigma,
int kernsize,
double lopt,
double aopt,
int iterations,
bool computeCovariance){
const char *const *argv double delta
double optimize(OrientedPoint &pnew, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
double registerScan(ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
void setSensorMap(const SensorMap &smap, std::string sensorName="FLASER")
void setRegistrationParameters(double regScore, double critScore)
void setMatchingParameters(double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations, bool computeCovariance=false)
const OrientedPoint & getPose() const
void setLaserParameters(unsigned int beams, double *angles, const OrientedPoint &lpose)
ScanMatcherProcessor(const ScanMatcherMap &m)
void invalidateActiveArea()
void eigen_decomposition(double A[n][n], double V[n][n], double d[n])
unsigned int rawView(double *v, double density=0.) const
virtual ~ScanMatcherProcessor()
std::map< std::string, Sensor * > SensorMap
virtual void processScan(const RangeReading &reading)
void setMatchingParameters(double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations, double likelihoodSigma=1, unsigned int likelihoodSkip=0)
double icpOptimize(OrientedPoint &pnew, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
OrientedPoint getPose() const
orientedpoint< double, double > OrientedPoint