Skip to content

Commit

Permalink
feat(pointcloud_preprocessor, probabilistic_occupancy_grid_map): enab…
Browse files Browse the repository at this point in the history
…le multi lidar occupancy grid map creation pipeline (autowarefoundation#740)

* add multi lidar pointcloud based ogm creation

Signed-off-by: yoshiri <[email protected]>

* enable sensing launch to control concatenate node

Signed-off-by: yoshiri <[email protected]>

* style(pre-commit): autofix

* refactor : change concatenate node parameter name

Signed-off-by: yoshiri <[email protected]>

* chore: set single lidar ogm to be default

Signed-off-by: yoshiri <[email protected]>

* feat: update multi_lidar_ogm param file

Signed-off-by: yoshiri <[email protected]>

* chore: remove sensing launch changes because it does not needed

Signed-off-by: yoshiri <[email protected]>

* chore: fix multi lidar settings for sample sensor kit

Signed-off-by: yoshiri <[email protected]>

---------

Signed-off-by: yoshiri <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and 4swinv committed Apr 9, 2024
1 parent 0cea6d6 commit 00ba18b
Show file tree
Hide file tree
Showing 3 changed files with 78 additions and 1 deletion.
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
# sample grid map fusion parameters for sample sensor kit
/**:
ros__parameters:
# shared parameters
shared_config:
map_frame: "map"
base_link_frame: "base_link"
# center of the grid map
gridmap_origin_frame: "base_link"

map_resolution: 0.5 # [m]
map_length_x: 150.0 # [m]
map_length_y: 150.0 # [m]

# each grid map parameters
ogm_creation_config:
height_filter:
use_height_filter: true
min_height: -1.0
max_height: 2.0
enable_single_frame_mode: true
# use sensor pointcloud to filter obstacle pointcloud
filter_obstacle_pointcloud_by_raw_pointcloud: true

grid_map_type: "OccupancyGridMapFixedBlindSpot"
OccupancyGridMapFixedBlindSpot:
distance_margin: 1.0
OccupancyGridMapProjectiveBlindSpot:
projection_dz_threshold: 0.01 # [m] for avoiding null division
obstacle_separation_threshold: 1.0 # [m] fill the interval between obstacles with unknown for this length
pub_debug_grid: false

# parameter settings for ogm fusion
fusion_config:
# following parameters are shared: map_frame, base_link_frame, gridmap_origin_frame, map_resolution, map_length
# Setting1: tune ogm creation parameters
raw_pointcloud_topics: # put each sensor's pointcloud topic
- "/sensing/lidar/top/pointcloud"
- "/sensing/lidar/left/pointcloud"
- "/sensing/lidar/right/pointcloud"
fusion_input_ogm_topics:
- "/perception/occupancy_grid_map/top_lidar/map"
- "/perception/occupancy_grid_map/left_lidar/map"
- "/perception/occupancy_grid_map/right_lidar/map"
# reliability of each sensor (0.0 ~ 1.0) only work with "log-odds" and "dempster-shafer"
input_ogm_reliabilities:
- 1.0
- 0.6
- 0.6

# Setting2: tune ogm fusion parameters
## choose fusion method from ["overwrite", "log-odds", "dempster-shafer"]
fusion_method: "overwrite"
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
/**:
ros__parameters:
# 1. fusion parameters
fusion_input_ogm_topics: ["topic1", "topic2"]
input_ogm_reliabilities: [0.8, 0.2]
fusion_method: "overwrite" # choose from ["overwrite", "log-odds", "dempster-shafer"]

# 2. synchronization settings
match_threshold_sec: 0.01 # 10ms
timeout_sec: 0.1 # 100ms
input_offset_sec: [0.0, 0.0] # no offset

# 3. settings for fused fusion map
# remember resolution and map size should be same with input maps
map_frame_: "map"
base_link_frame_: "base_link"
grid_map_origin_frame_: "base_link"
fusion_map_length_x: 100.0
fusion_map_length_y: 100.0
fusion_map_resolution: 0.5
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
<?xml version="1.0"?>
<launch>
<arg name="occupancy_grid_map_method" default="pointcloud_based_occupancy_grid_map" description="options: pointcloud_based_occupancy_grid_map, laserscan_based_occupancy_grid_map"/>
<arg
name="occupancy_grid_map_method"
default="pointcloud_based_occupancy_grid_map"
description="options: pointcloud_based_occupancy_grid_map, laserscan_based_occupancy_grid_map, multi_lidar_pointcloud_based_occupancy_grid_map"
/>
<arg name="occupancy_grid_map_updater" default="binary_bayes_filter" description="options: binary_bayes_filter"/>
<arg name="detected_objects_filter_method" default="lanelet_filter" description="options: lanelet_filter, position_filter"/>
<arg
Expand Down

0 comments on commit 00ba18b

Please sign in to comment.