Outdoor mapping, sky noises

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Outdoor mapping, sky noises

dizeng
Hey mathieu,

The demo went very well last Wednesday, we went to the raspberry filed and did some test also.

I encountered issues as sky being mapped into the point cloud. How do I filter out the sky while doing mapping outdoor?




Thanks
Reply | Threaded
Open this post in threaded view
|

Re: Outdoor mapping, sky noises

matlabbe
Administrator
Hi Di,

good to know that the demo went well!

For the point cloud, you may limit the depth of the created point clouds. You could also look at the ZED parameters if there are some parameters to clean the generated depth image. Looking at the ros-zed-wrapper, there is a dynamic parameter called "confidence" that can be used (use "$ rosrun rqt_reconfigure rqt_reconfigure" to change it dynamically). Setting "quality" to "Quality" may also help to reduce the noise (but more computation power is required).

There is limited cloud post-filtering in rtabmap. To clean /rtabmap/cloud_map topic, you can tune these parameters (default values shown below and in the same order than the filtering pipeline):
<node pkg="rtabmap_ros" name="rtabmap" type="rtabmap">

   <param name="cloud_decimation" value="4"/>                <!-- 0=inf -->

   <!-- ref: http://www.pointclouds.org/documentation/tutorials/passthrough.php#passthrough -->
   <param name="cloud_max_depth" value="4.0"/>               <!-- 0=inf -->

   <!-- ref: http://www.pointclouds.org/documentation/tutorials/voxel_grid.php#voxelgrid -->
   <param name="cloud_voxel_size" value="0.05"/>             <!-- 0=Disabled -->

   <!-- ref: http://www.pointclouds.org/documentation/tutorials/remove_outliers.php#remove-outliers -->
   <param name="cloud_noise_filtering_radius" value="0.0"/>  <!-- 0=Disabled -->
   <param name="cloud_noise_filtering_min_neighbors" value="5"/>
   ...
</node>

cheers,
Mathieu