For the main question, yes you can feed both sensors to update the local costmap. See https://github.com/introlab/rtabmap_r... for such example:
global_frame: odom
robot_base_frame: base_footprint
update_frequency: 2.0
publish_frequency: 2.0
rolling_window: true
width: 4.0
height: 4.0
resolution: 0.025
origin_x: -2.0
origin_y: -2.0
plugins:
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
obstacle_layer:
obstacle_range: 2.5
raytrace_range: 3.0
max_obstacle_height: 0.4
track_unknown_space: true
observation_sources: laser_scan_sensor point_cloud_sensorA point_cloud_sensorB
laser_scan_sensor: {
data_type: LaserScan,
topic: /base_scan,
expected_update_rate: 0.2,
marking: true,
clearing: true
}
point_cloud_sensorA: {
sensor_frame: base_footprint,
data_type: PointCloud2,
topic: /obstacles_cloud,
expected_update_rate: 0.5,
marking: true,
clearing: true,
min_obstacle_height: 0.04
}
point_cloud_sensorB: {
sensor_frame: base_footprint,
data_type: PointCloud2,
topic: /ground_cloud,
expected_update_rate: 0.5,
marking: false,
clearing: true,
min_obstacle_height: -1.0 # make usre the ground is not filtered
}
The ground and obstacle coulds are generated like in this file:
<group ns="camera">
<!-- camera_nodelet_manager started by openni or freenect -->
<node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle camera_nodelet_manager">
<param name="rate" type="double" value="5"/>
<param name="decimation" type="int" value="2"/>
<remap from="rgb/image_in" to="rgb/image_rect_color"/>
<remap from="depth/image_in" to="depth_registered/image_raw"/>
<remap from="rgb/camera_info_in" to="rgb/camera_info"/>
<remap from="rgb/image_out" to="data_resized_image"/>
<remap from="depth/image_out" to="data_resized_image_depth"/>
<remap from="rgb/camera_info_out" to="data_resized_camera_info"/>
</node>
<!-- for the planner -->
<node pkg="nodelet" type="nodelet" name="points_xyz_planner" args="load rtabmap_ros/point_cloud_xyz camera_nodelet_manager">
<remap from="depth/image" to="data_resized_image_depth"/>
<remap from="depth/camera_info" to="data_resized_camera_info"/>
<remap from="cloud" to="cloudXYZ" />
<param name="decimation" type="int" value="1"/> <!-- already decimated above -->
<param name="max_depth" type="double" value="3.0"/>
<param name="voxel_size" type="double" value="0.02"/>
</node>
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection camera_nodelet_manager">
<remap from="cloud" to="cloudXYZ"/>
<remap from="obstacles" to="/obstacles_cloud"/>
<remap from="ground" to="/ground_cloud"/>
<param name="frame_id" type="string" value="base_footprint"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="wait_for_transform" type="bool" value="true"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.4"/>
</node>
</group>
cheers,
Mathieu