openslam_gmapping icon indicating copy to clipboard operation
openslam_gmapping copied to clipboard

question about ScanMatcher::score

Open asmashine opened this issue 8 years ago • 5 comments

in this function ,to caculate pfree,there are double freeDelta=map.getDelta()*m_freeCellRatio;and pfree.x+=(*r-map.getDelta()*freeDelta)*cos(lp.theta+*angle); pfree.y+=(*r-map.getDelta()*freeDelta)*sin(lp.theta+*angle);; obviously r - delta^2sqrt(2) (freeDelta = sqrt(2))
i think r - delta
sqart(2) can show the range of pfree ,but the equation above i don't know its mean.

asmashine avatar Feb 18 '17 04:02 asmashine

me too! I need the explanation.

lmy19880626 avatar May 09 '17 12:05 lmy19880626

I have the same question ,have you sloved it?

KOTOKORURU avatar Mar 09 '18 02:03 KOTOKORURU

me too! I think there's a bug!

1344618323 avatar Aug 10 '19 14:08 1344618323

I think this is a bug that was shadowed by another bug, https://github.com/ros-perception/openslam_gmapping/issues/25 making everything about pfree, ipfree, pf and fcell irrelevant.

And yes,

pfree.x+=(*r-map.getDelta()*freeDelta)*cos(lp.theta+*angle);
pfree.y+=(*r-map.getDelta()*freeDelta)*sin(lp.theta+*angle);

should be replaced with

pfree.x+=(*r-*freeDelta)*cos(lp.theta+*angle);
pfree.y+=(*r-*freeDelta)*sin(lp.theta+*angle);

With these two bugs solved, gmapping stops looking for best score inside a wall.

topin89 avatar Nov 03 '19 20:11 topin89

Oh, there is a PR to fix that: https://github.com/ros-perception/openslam_gmapping/pull/10

topin89 avatar Nov 03 '19 20:11 topin89