include
gmapping
gridfastslam
gridslamprocessor.h
Go to the documentation of this file.
1
#ifndef GRIDSLAMPROCESSOR_H
2
#define GRIDSLAMPROCESSOR_H
3
4
#include <climits>
5
#include <limits>
6
#include <fstream>
7
#include <vector>
8
#include <deque>
9
#include <
gmapping/particlefilter/particlefilter.h
>
10
#include <
gmapping/utils/point.h
>
11
#include <
gmapping/utils/macro_params.h
>
12
#include <
gmapping/log/sensorlog.h
>
13
#include <
gmapping/sensor/sensor_range/rangesensor.h
>
14
#include <
gmapping/sensor/sensor_range/rangereading.h
>
15
#include <
gmapping/scanmatcher/scanmatcher.h
>
16
#include "
gmapping/gridfastslam/motionmodel.h
"
17
#include <gmapping/gridfastslam/gridfastslam_export.h>
18
19
20
namespace
GMapping
{
21
35
class
GRIDFASTSLAM_EXPORT
GridSlamProcessor
{
36
public
:
37
38
43
struct
TNode
{
51
TNode
(
const
OrientedPoint
& pose,
double
weight,
TNode
* parent=0,
unsigned
int
childs=0);
52
55
~
TNode
();
56
58
OrientedPoint
pose
;
59
61
double
weight
;
62
64
double
accWeight
;
65
66
double
gweight
;
67
68
70
TNode
*
parent
;
71
73
const
RangeReading
*
reading
;
74
76
unsigned
int
childs
;
77
79
mutable
unsigned
int
visitCounter
;
80
82
mutable
bool
flag
;
83
};
84
85
typedef
std::vector<GridSlamProcessor::TNode*>
TNodeVector
;
86
typedef
std::deque<GridSlamProcessor::TNode*>
TNodeDeque
;
87
89
struct
Particle
{
93
Particle
(
const
ScanMatcherMap
& map);
94
96
inline
operator
double()
const
{
return
weight;}
98
inline
operator
OrientedPoint
()
const
{
return
pose;}
102
inline
void
setWeight
(
double
w) {weight=w;}
104
ScanMatcherMap
map
;
106
OrientedPoint
pose
;
107
109
OrientedPoint
previousPose
;
110
112
double
weight
;
113
115
double
weightSum
;
116
117
double
gweight
;
118
120
int
previousIndex
;
121
123
TNode
*
node
;
124
};
125
126
127
typedef
std::vector<Particle>
ParticleVector
;
128
130
GridSlamProcessor
();
131
135
GridSlamProcessor
(std::ostream& infoStr);
136
139
GridSlamProcessor
* clone()
const
;
140
142
virtual
~
GridSlamProcessor
();
143
144
//methods for accessing the parameters
145
void
setSensorMap(
const
SensorMap
& smap);
146
void
init(
unsigned
int
size,
double
xmin,
double
ymin,
double
xmax,
double
ymax,
double
delta
,
147
OrientedPoint
initialPose=
OrientedPoint
(0,0,0));
148
void
setMatchingParameters(
double
urange,
double
range,
double
sigma,
int
kernsize,
double
lopt,
double
aopt,
149
int
iterations,
double
likelihoodSigma=1,
double
likelihoodGain=1,
unsigned
int
likelihoodSkip=0);
150
void
setMotionModelParameters(
double
srr,
double
srt,
double
str,
double
stt);
151
void
setUpdateDistances(
double
linear,
double
angular,
double
resampleThreshold);
152
void
setUpdatePeriod
(
double
p) {period_=p;}
153
154
//the "core" algorithm
155
void
processTruePos(
const
OdometryReading
& odometry);
156
bool
processScan(
const
RangeReading
& reading,
int
adaptParticles=0);
157
163
TNodeVector getTrajectories()
const
;
164
void
integrateScanSequence(TNode* node);
165
167
ScanMatcher
m_matcher
;
169
std::ofstream& outputStream();
171
std::ostream& infoStream();
173
inline
const
ParticleVector
&
getParticles
()
const
{
return
m_particles; }
174
175
inline
const
std::vector<unsigned int>&
getIndexes
()
const
{
return
m_indexes; }
176
int
getBestParticleIndex()
const
;
177
//callbacks
178
virtual
void
onOdometryUpdate();
179
virtual
void
onResampleUpdate();
180
virtual
void
onScanmatchUpdate();
181
182
//accessor methods
184
MEMBER_PARAM_SET_GET
(m_matcher,
double
, laserMaxRange,
protected
,
public
,
public
);
185
187
MEMBER_PARAM_SET_GET
(m_matcher,
double
, usableRange,
protected
,
public
,
public
);
188
190
MEMBER_PARAM_SET_GET
(m_matcher,
double
, gaussianSigma,
protected
,
public
,
public
);
191
193
MEMBER_PARAM_SET_GET
(m_matcher,
double
, likelihoodSigma,
protected
,
public
,
public
);
194
196
MEMBER_PARAM_SET_GET
(m_matcher,
int
, kernelSize,
protected
,
public
,
public
);
197
199
MEMBER_PARAM_SET_GET
(m_matcher,
double
, optAngularDelta,
protected
,
public
,
public
);
200
202
MEMBER_PARAM_SET_GET
(m_matcher,
double
, optLinearDelta,
protected
,
public
,
public
);
203
205
MEMBER_PARAM_SET_GET
(m_matcher,
unsigned
int
, optRecursiveIterations,
protected
,
public
,
public
);
206
208
MEMBER_PARAM_SET_GET
(m_matcher,
unsigned
int
, likelihoodSkip,
protected
,
public
,
public
);
209
211
MEMBER_PARAM_SET_GET
(m_matcher,
double
, llsamplerange,
protected
,
public
,
public
);
212
214
MEMBER_PARAM_SET_GET
(m_matcher,
double
, lasamplerange,
protected
,
public
,
public
);
215
217
MEMBER_PARAM_SET_GET
(m_matcher,
double
, llsamplestep,
protected
,
public
,
public
);
218
220
MEMBER_PARAM_SET_GET
(m_matcher,
double
, lasamplestep,
protected
,
public
,
public
);
221
223
MEMBER_PARAM_SET_GET
(m_matcher,
bool
, generateMap,
protected
,
public
,
public
);
224
226
MEMBER_PARAM_SET_GET
(m_matcher,
bool
, enlargeStep,
protected
,
public
,
public
);
227
229
MEMBER_PARAM_SET_GET
(m_matcher,
OrientedPoint
, laserPose,
protected
,
public
,
public
);
230
231
233
STRUCT_PARAM_SET_GET
(m_motionModel,
double
, srr,
protected
,
public
,
public
);
234
236
STRUCT_PARAM_SET_GET
(m_motionModel,
double
, srt,
protected
,
public
,
public
);
237
239
STRUCT_PARAM_SET_GET
(m_motionModel,
double
, str,
protected
,
public
,
public
);
240
242
STRUCT_PARAM_SET_GET
(m_motionModel,
double
, stt,
protected
,
public
,
public
);
243
245
PARAM_SET_GET
(
double
, minimumScore,
protected
,
public
,
public
);
246
247
protected
:
249
GridSlamProcessor
(
const
GridSlamProcessor
& gsp);
250
252
unsigned
int
m_beams
;
253
double
last_update_time_
;
254
double
period_
;
255
257
ParticleVector
m_particles
;
258
260
std::vector<unsigned int>
m_indexes
;
261
263
std::vector<double>
m_weights
;
264
266
MotionModel
m_motionModel
;
267
269
PARAM_SET_GET
(
double
, resampleThreshold,
protected
,
public
,
public
);
270
271
//state
272
int
m_count,
m_readingCount
;
273
OrientedPoint
m_lastPartPose
;
274
OrientedPoint
m_odoPose
;
275
OrientedPoint
m_pose
;
276
double
m_linearDistance
, m_angularDistance;
277
PARAM_GET
(
double
,
neff
,
protected
,
public
);
278
279
//processing parameters (size of the map)
280
PARAM_GET
(
double
, xmin,
protected
,
public
);
281
PARAM_GET
(
double
, ymin,
protected
,
public
);
282
PARAM_GET
(
double
, xmax,
protected
,
public
);
283
PARAM_GET
(
double
, ymax,
protected
,
public
);
284
//processing parameters (resolution of the map)
285
PARAM_GET
(
double
,
delta
,
protected
,
public
);
286
287
//registration score (if a scan score is above this threshold it is registered in the map)
288
PARAM_SET_GET
(
double
, regScore,
protected
,
public
,
public
);
289
//registration score (if a scan score is below this threshold a scan matching failure is reported)
290
PARAM_SET_GET
(
double
, critScore,
protected
,
public
,
public
);
291
//registration score maximum move allowed between consecutive scans
292
PARAM_SET_GET
(
double
, maxMove,
protected
,
public
,
public
);
293
294
//process a scan each time the robot translates of linearThresholdDistance
295
PARAM_SET_GET
(
double
, linearThresholdDistance,
protected
,
public
,
public
);
296
297
//process a scan each time the robot rotates more than angularThresholdDistance
298
PARAM_SET_GET
(
double
, angularThresholdDistance,
protected
,
public
,
public
);
299
300
//smoothing factor for the likelihood
301
PARAM_SET_GET
(
double
, obsSigmaGain,
protected
,
public
,
public
);
302
303
//stream in which to write the gfs file
304
std::ofstream
m_outputStream
;
305
306
// stream in which to write the messages
307
std::ostream&
m_infoStream
;
308
309
310
// the functions below performs side effect on the internal structure,
311
//should be called only inside the processScan method
312
private
:
313
315
inline
void
scanMatch(
const
double
*plainReading);
317
inline
void
normalize
();
318
319
// return if a resampling occured or not
320
inline
bool
resample
(
const
double
* plainReading,
int
adaptParticles,
321
const
RangeReading
* rr=0);
322
323
//tree utilities
324
325
void
updateTreeWeights(
bool
weightsAlreadyNormalized =
false
);
326
void
resetTree();
327
double
propagateWeights();
328
329
};
330
331
typedef
std::multimap<const GridSlamProcessor::TNode*, GridSlamProcessor::TNode*>
TNodeMultimap
;
332
333
334
#include "gmapping/gridfastslam/gridslamprocessor.hxx"
335
336
};
337
338
#endif
GMapping::GridSlamProcessor::getIndexes
const std::vector< unsigned int > & getIndexes() const
Definition:
gridslamprocessor.h:175
GMapping::GridSlamProcessor::m_odoPose
OrientedPoint m_odoPose
Definition:
gridslamprocessor.h:274
GMapping::GridSlamProcessor::m_linearDistance
double m_linearDistance
Definition:
gridslamprocessor.h:276
GMapping::SensorMap
std::map< std::string, Sensor * > SensorMap
Definition:
sensor.h:20
GMapping::GridSlamProcessor::Particle::previousPose
OrientedPoint previousPose
Definition:
gridslamprocessor.h:109
GMapping::GridSlamProcessor::Particle::previousIndex
int previousIndex
Definition:
gridslamprocessor.h:120
point.h
rangesensor.h
particlefilter.h
GMapping::GridSlamProcessor::Particle::weight
double weight
Definition:
gridslamprocessor.h:112
GMapping::GridSlamProcessor::TNode::childs
unsigned int childs
Definition:
gridslamprocessor.h:76
normalize
void normalize(const Iterator &begin, const Iterator &end)
Definition:
particlefilter.h:112
GMapping::GridSlamProcessor::TNodeVector
std::vector< GridSlamProcessor::TNode * > TNodeVector
Definition:
gridslamprocessor.h:85
GMapping::GridSlamProcessor::ParticleVector
std::vector< Particle > ParticleVector
Definition:
gridslamprocessor.h:127
STRUCT_PARAM_SET_GET
#define STRUCT_PARAM_SET_GET(member, type, name, qualifier, setqualifier, getqualifier)
Definition:
macro_params.h:27
GMapping::GridSlamProcessor::TNode::reading
const RangeReading * reading
Definition:
gridslamprocessor.h:73
GMapping::GridSlamProcessor::TNode::visitCounter
unsigned int visitCounter
Definition:
gridslamprocessor.h:79
GMapping
Definition:
configfile.cpp:34
GMapping::GridSlamProcessor::m_weights
std::vector< double > m_weights
Definition:
gridslamprocessor.h:263
GMapping::GridSlamProcessor::m_matcher
ScanMatcher m_matcher
Definition:
gridslamprocessor.h:167
PARAM_SET_GET
#define PARAM_SET_GET(type, name, qualifier, setqualifier, getqualifier)
Definition:
macro_params.h:4
GMapping::GridSlamProcessor::m_pose
OrientedPoint m_pose
Definition:
gridslamprocessor.h:275
GMapping::GridSlamProcessor::Particle::pose
OrientedPoint pose
Definition:
gridslamprocessor.h:106
GMapping::GridSlamProcessor::m_indexes
std::vector< unsigned int > m_indexes
Definition:
gridslamprocessor.h:260
sensorlog.h
GMapping::ScanMatcher
Definition:
scanmatcher.h:15
delta
const char *const *argv double delta
Definition:
gfs2stream.cpp:19
macro_params.h
GMapping::Map< PointAccumulator, HierarchicalArray2D< PointAccumulator > >
GMapping::GridSlamProcessor::m_lastPartPose
OrientedPoint m_lastPartPose
Definition:
gridslamprocessor.h:273
GMapping::OrientedPoint
orientedpoint< double, double > OrientedPoint
Definition:
point.h:203
GMapping::TNodeMultimap
std::multimap< const GridSlamProcessor::TNode *, GridSlamProcessor::TNode * > TNodeMultimap
Definition:
gridslamprocessor.h:331
GMapping::GridSlamProcessor::TNodeDeque
std::deque< GridSlamProcessor::TNode * > TNodeDeque
Definition:
gridslamprocessor.h:86
GMapping::GridSlamProcessor::Particle::setWeight
void setWeight(double w)
Definition:
gridslamprocessor.h:102
GMapping::MotionModel
Definition:
motionmodel.h:10
GMapping::OdometryReading
Definition:
odometryreading.h:12
scanmatcher.h
GMapping::GridSlamProcessor
Definition:
gridslamprocessor.h:35
GMapping::GridSlamProcessor::m_outputStream
std::ofstream m_outputStream
Definition:
gridslamprocessor.h:304
GMapping::GridSlamProcessor::Particle
Definition:
gridslamprocessor.h:89
GMapping::GridSlamProcessor::Particle::node
TNode * node
Definition:
gridslamprocessor.h:123
GMapping::GridSlamProcessor::TNode::flag
bool flag
Definition:
gridslamprocessor.h:82
GMapping::GridSlamProcessor::TNode::parent
TNode * parent
Definition:
gridslamprocessor.h:70
GMapping::GridSlamProcessor::TNode
Definition:
gridslamprocessor.h:43
GMapping::GridSlamProcessor::TNode::gweight
double gweight
Definition:
gridslamprocessor.h:66
GMapping::GridSlamProcessor::getParticles
const ParticleVector & getParticles() const
Definition:
gridslamprocessor.h:173
GMapping::GridSlamProcessor::m_particles
ParticleVector m_particles
Definition:
gridslamprocessor.h:257
rangereading.h
GMapping::GridSlamProcessor::Particle::weightSum
double weightSum
Definition:
gridslamprocessor.h:115
GMapping::GridSlamProcessor::period_
double period_
Definition:
gridslamprocessor.h:254
MEMBER_PARAM_SET_GET
#define MEMBER_PARAM_SET_GET(member, type, name, qualifier, setqualifier, getqualifier)
Definition:
macro_params.h:17
GMapping::RangeReading
Definition:
rangereading.h:17
neff
bool neff
Definition:
gfs2stream.cpp:39
GMapping::GridSlamProcessor::m_motionModel
MotionModel m_motionModel
Definition:
gridslamprocessor.h:266
GMapping::GridSlamProcessor::TNode::pose
OrientedPoint pose
Definition:
gridslamprocessor.h:58
GMapping::GridSlamProcessor::last_update_time_
double last_update_time_
Definition:
gridslamprocessor.h:253
GMapping::GridSlamProcessor::m_readingCount
int m_readingCount
Definition:
gridslamprocessor.h:272
GMapping::GridSlamProcessor::setUpdatePeriod
void setUpdatePeriod(double p)
Definition:
gridslamprocessor.h:152
GMapping::GridSlamProcessor::Particle::map
ScanMatcherMap map
Definition:
gridslamprocessor.h:104
motionmodel.h
resample
void resample(std::vector< int > &indexes, const WeightVector &weights, unsigned int nparticles=0)
Definition:
particlefilter.h:51
GMapping::GridSlamProcessor::m_beams
unsigned int m_beams
Definition:
gridslamprocessor.h:252
GMapping::GridSlamProcessor::TNode::accWeight
double accWeight
Definition:
gridslamprocessor.h:64
GMapping::orientedpoint< double, double >
GMapping::GridSlamProcessor::m_infoStream
std::ostream & m_infoStream
Definition:
gridslamprocessor.h:307
PARAM_GET
#define PARAM_GET(type, name, qualifier, getqualifier)
Definition:
macro_params.h:13
GMapping::GridSlamProcessor::TNode::weight
double weight
Definition:
gridslamprocessor.h:61
GMapping::GridSlamProcessor::Particle::gweight
double gweight
Definition:
gridslamprocessor.h:117
openslam_gmapping
Author(s): Cyrill Stachniss, Udo Frese, Giorgio Grisetti, Wolfram Burgard
autogenerated on Thu Oct 19 2023 02:25:51