How to tune obstacle map generation with nodelet

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

How to tune obstacle map generation with nodelet

ibd
Hi all

I am running rtabmap together with move_base for navigation.
I run rtabmap in its own node through a .launch file, and I also run the obstacle_detection nodelet like this:
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection rtabmap_pc_processing" output="screen">
    <remap from="cloud" to="tango_point_cloud_relay"/>
    <remap from="obstacles" to="/obstacles_cloud"/>
    <remap from="ground"    to="/ground_cloud"/>

    <param name="frame_id"             type="string" value="base_link"/>    
    <param name="map_frame_id"         type="string" value="map"/>
    <param name="wait_for_transform"   type="bool" value="true"/>
  </node>

I have some problems with the resulting obstacle map generation:
1. Some scans will produce stray "obstacles" on the ground, this results in spurious obstacle "lines" on the ground. I reckon it comes from point normal estimation. This is a problem for the static_layer in move_base, as it directly inflates the obstacle map without 3D reasoning.
2. I have some obstacles like traffic cones that have a low deviation from ground plane normal near their perimeter. These are wrongly not detected as obstacles. When I check the generated cloud of obstacles, I can see that these parts of the perimeter are treated like "ground" instead of "obstacle". This is a problem for the local costmap, because it depends on this cloud for generating costmaps on-the-fly at high rates. Again I think this can be solved by tuning normal estimation.
BTW, the local costmap looks like this, copied and adapted from another post here:
obstacles_laser:
  observation_sources: obstacles_obs ground_obs
  obstacles_obs: {
    data_type: PointCloud2,
    topic: /obstacles_cloud,
    max_obstacle_height: 3.0,
    min_obstacle_height: 0.04,
    marking: true,
    clearing: true
  }

  ground_obs: {
    data_type: PointCloud2,
    topic: /ground_cloud,
    max_obstacle_height: 0.5,
    min_obstacle_height: -1.0, # make sure the ground is filtered
    marking: false,
    clearing: true
  }


I tried tuning the parameters of the obstacle_detection nodelet, namely the k neighbors used for estimating, and the maximum angle deviation from ground plane. However, when I change these parameters, I get a ROS_ERROR saying something like "this parameter is deprecated, it has been copied to rtabmap. The original name is ... and the new name is ...". I notice that there is no change in behavior in the actual nodelet, nor is there any change in RTABMAP itself.
If I try to tune these parameters as RTABMAP parameters in the launch file, the obstacle map as generated by RTABMAP (/rtabmap/grid_map) will reflect the changed parameters. Obviously, the nodelet's behavior is not affeceted.
Thus my question:
3. How can I tune these parameters that are seemingly deprecated in the nodelet?

Best regards
ibd
Reply | Threaded
Open this post in threaded view
|

Re: How to tune obstacle map generation with nodelet

matlabbe
Administrator
Hi,

The obstacles_detection nodelet has been updated to use exactly the same parameters than those used for the static map created by rtabmap node (same algorithm is used). You can copy/paste the "Grid/" parameters set for rtabmap node to obstacles_detection nodelet.

Note that old parameters would still work: normally it should still convert the deprecated parameters if it is a warning on terminal, but not for errors, which tell that parameters could not be matched with new parameters (so they won't work).

For a list of obstacles_detection parameter, do:
$ rtabmap --params | grep Grid/

cheers,
Mathieu