diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml index d3ab3718f15a4999c0b8b062f57bb873908721cb..cb5d6e8712e31f8ae6b5616cfd015144e2733c0d 100644 --- a/params/costmap/common_params.yaml +++ b/params/costmap/common_params.yaml @@ -22,7 +22,7 @@ obstacle_layer: max_obstacle_height: 1.0 footprint_clearing_enabled: false combination_method: 1 - observation_sources: velodyne #depth_cam + observation_sources: velodyne velodyne_ground #depth_cam velodyne: { sensor_frame: helena/robosense, @@ -37,6 +37,19 @@ obstacle_layer: obstacle_range: 30.0, raytrace_range: 40.0 } + velodyne_ground: { + sensor_frame: helena/robosense, + data_type: PointCloud2, + topic: /helena/sensors/rslidar_points, + observation_persistence: 0.0, + marking: false, + clearing: true, + min_obstacle_height: -1.0, + max_obstacle_height: 0.05, + expected_update_rate: 1, + obstacle_range: 30.0, + raytrace_range: 40.0 + } depth_cam: { sensor_frame: helena/camera_color_optical_frame,