Skip to content

Commit 5a606e0

Browse files
feat(pointcloud_preprocessor, probabilistic_occupancy_grid_map): enable multi lidar occupancy grid map creation pipeline (#740)
* add multi lidar pointcloud based ogm creation Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * enable sensing launch to control concatenate node Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * style(pre-commit): autofix * refactor : change concatenate node parameter name Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * chore: set single lidar ogm to be default Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * feat: update multi_lidar_ogm param file Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * chore: remove sensing launch changes because it does not needed Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * chore: fix multi lidar settings for sample sensor kit Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> --------- Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 5aced52 commit 5a606e0

File tree

3 files changed

+78
-1
lines changed

3 files changed

+78
-1
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
# sample grid map fusion parameters for sample sensor kit
2+
/**:
3+
ros__parameters:
4+
# shared parameters
5+
shared_config:
6+
map_frame: "map"
7+
base_link_frame: "base_link"
8+
# center of the grid map
9+
gridmap_origin_frame: "base_link"
10+
11+
map_resolution: 0.5 # [m]
12+
map_length_x: 150.0 # [m]
13+
map_length_y: 150.0 # [m]
14+
15+
# each grid map parameters
16+
ogm_creation_config:
17+
height_filter:
18+
use_height_filter: true
19+
min_height: -1.0
20+
max_height: 2.0
21+
enable_single_frame_mode: true
22+
# use sensor pointcloud to filter obstacle pointcloud
23+
filter_obstacle_pointcloud_by_raw_pointcloud: true
24+
25+
grid_map_type: "OccupancyGridMapFixedBlindSpot"
26+
OccupancyGridMapFixedBlindSpot:
27+
distance_margin: 1.0
28+
OccupancyGridMapProjectiveBlindSpot:
29+
projection_dz_threshold: 0.01 # [m] for avoiding null division
30+
obstacle_separation_threshold: 1.0 # [m] fill the interval between obstacles with unknown for this length
31+
pub_debug_grid: false
32+
33+
# parameter settings for ogm fusion
34+
fusion_config:
35+
# following parameters are shared: map_frame, base_link_frame, gridmap_origin_frame, map_resolution, map_length
36+
# Setting1: tune ogm creation parameters
37+
raw_pointcloud_topics: # put each sensor's pointcloud topic
38+
- "/sensing/lidar/top/pointcloud"
39+
- "/sensing/lidar/left/pointcloud"
40+
- "/sensing/lidar/right/pointcloud"
41+
fusion_input_ogm_topics:
42+
- "/perception/occupancy_grid_map/top_lidar/map"
43+
- "/perception/occupancy_grid_map/left_lidar/map"
44+
- "/perception/occupancy_grid_map/right_lidar/map"
45+
# reliability of each sensor (0.0 ~ 1.0) only work with "log-odds" and "dempster-shafer"
46+
input_ogm_reliabilities:
47+
- 1.0
48+
- 0.6
49+
- 0.6
50+
51+
# Setting2: tune ogm fusion parameters
52+
## choose fusion method from ["overwrite", "log-odds", "dempster-shafer"]
53+
fusion_method: "overwrite"
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
/**:
2+
ros__parameters:
3+
# 1. fusion parameters
4+
fusion_input_ogm_topics: ["topic1", "topic2"]
5+
input_ogm_reliabilities: [0.8, 0.2]
6+
fusion_method: "overwrite" # choose from ["overwrite", "log-odds", "dempster-shafer"]
7+
8+
# 2. synchronization settings
9+
match_threshold_sec: 0.01 # 10ms
10+
timeout_sec: 0.1 # 100ms
11+
input_offset_sec: [0.0, 0.0] # no offset
12+
13+
# 3. settings for fused fusion map
14+
# remember resolution and map size should be same with input maps
15+
map_frame_: "map"
16+
base_link_frame_: "base_link"
17+
grid_map_origin_frame_: "base_link"
18+
fusion_map_length_x: 100.0
19+
fusion_map_length_y: 100.0
20+
fusion_map_resolution: 0.5

autoware_launch/launch/components/tier4_perception_component.launch.xml

+5-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
11
<?xml version="1.0"?>
22
<launch>
3-
<arg name="occupancy_grid_map_method" default="pointcloud_based_occupancy_grid_map" description="options: pointcloud_based_occupancy_grid_map, laserscan_based_occupancy_grid_map"/>
3+
<arg
4+
name="occupancy_grid_map_method"
5+
default="pointcloud_based_occupancy_grid_map"
6+
description="options: pointcloud_based_occupancy_grid_map, laserscan_based_occupancy_grid_map, multi_lidar_pointcloud_based_occupancy_grid_map"
7+
/>
48
<arg name="occupancy_grid_map_updater" default="binary_bayes_filter" description="options: binary_bayes_filter"/>
59
<arg name="detected_objects_filter_method" default="lanelet_filter" description="options: lanelet_filter, position_filter"/>
610
<arg

0 commit comments

Comments
 (0)