0
$\begingroup$

Rosanswers logo

Hi,All,

I am using a 3D lidar together with octomap package to build a 3D map for an indoor environment. Since my lidar is stationary, I actually don't need any transform between lidar frame and map frame. Everything works fine except that when there are moving objects, the 3D map produced seems to be messy. Those occupied cells are not cleared even when the moving objects moved away. I know this has sth to do with the update rule of the octomap and I have been trying to play around with the octomap parameters but no success. What am I missing here? Thanks a lot!

My platform: Ubuntu 12.04, ROS Fuerte, Octomap is the one checked out from ROS wiki page.


Originally posted by BenMa on ROS Answers with karma: 76 on 2013-09-09

Post score: 1


Original comments

Comment by dornhege on 2013-09-09:
They should be cleared. Are they not changing at all or at least changing a bit, but slowly? Were they at max likelihood before? Are you getting lidar measurements through the places where objects were?

Comment by BenMa on 2013-09-09:
Another strange observation: if I pass the PCL2 generated by the lidar directly to the octomap server, the dynamic objects are actually cleared!. However, if I use the PCL filter (such as outlier removal) to filter the raw PCL2 and pass the filtered PCL2 to the octomap server, the dynamic objects are not cleared. A walking person will left a trail (3D cells) behind him. And, sometimes I got "Not enough inliners found to support a model (0)! returning the same coefficients" error.

Back to your questions: Where can I check max likelihood? My lidar is in the centre of an indoor space where people walked by occasionally.

Comment by dornhege on 2013-09-09:
That seems to me like the filter, filters out something. Might be time to look at both point clouds and see what's happening.

Comment by BenMa on 2013-09-09:
The filtered PCL looks normal, at least in rviz.

Comment by dornhege on 2013-09-09:
Is it maybe downsampled?

Comment by BenMa on 2013-09-09:
In the case of voxel filter, the PCL are downsampled. The dynamic object won't clear completely. It left a sparse trail behind. In the case of passthroughfilter (Z axis), the PCL are limted to certain height, the dynamic object will left a trail on the floor.

Comment by dornhege on 2013-09-10:
I guess that might be the problem. If it's downsampled, you have less end points to go through. Thus you get some traces, but not enough, so that some cells "in between" the rays are never visited and thus not cleared. If that's the case it should look like the objects are "thinned out in density".

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Remove the passthrough filter with a z-range limit.

There is a configurable z-range limit which you can configure instead directly in octomap_server. You should include enough of the z range so that the ground plane can be used for clearing obstacles. When you cut it away, you can no longer clear obstacles in between. Instead, just enable the ground plane filter in octomap_server, it will clear properly.

Edit regarding voxel grid filter: It's usually a good idea to run that in order to speed up the integration in OctoMap. However, you must choose a resolution at most as small as your octomap resolution.


Originally posted by AHornung with karma: 5904 on 2013-09-10

This answer was ACCEPTED on the original site

Post score: 1


Original comments

Comment by BenMa on 2013-09-10:
It works! Thank a lot! "You should include enough of the z range so that the ground plane can be used for clearing obstacles. When you cut it away, you can no longer clear obstacles in between", why this happened? Could you explain a bit more? Thanks!

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.