diff --git a/edge_auto_launch/config/roi_cluster_fusion.param.yaml b/edge_auto_launch/config/roi_cluster_fusion.param.yaml new file mode 100644 index 0000000..e8c9f85 --- /dev/null +++ b/edge_auto_launch/config/roi_cluster_fusion.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + fusion_distance: 100.0 + trust_object_distance: 100.0 + trust_object_iou_mode: "iou" + non_trust_object_iou_mode: "iou" + use_cluster_semantic_type: false + # only_allow_inside_cluster: true + only_allow_inside_cluster: false + roi_scale_factor: 1.1 + iou_threshold: 0.3 + unknown_iou_threshold: 0.1 + remove_unknown: true + debug_mode: true + image_buffer_size: 1000 + diff --git a/edge_auto_launch/config/scan_ground_filter.param.yaml b/edge_auto_launch/config/scan_ground_filter.param.yaml index cd18c66..35d494a 100644 --- a/edge_auto_launch/config/scan_ground_filter.param.yaml +++ b/edge_auto_launch/config/scan_ground_filter.param.yaml @@ -1,6 +1,18 @@ /**: ros__parameters: global_slope_max_angle_deg: 10.0 - local_slope_max_angle_deg: 30.0 + local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode split_points_distance_tolerance: 0.2 + use_virtual_ground_point: True split_height_distance: 0.2 + non_ground_height_threshold: 0.20 + grid_size_m: 0.1 + grid_mode_switch_radius: 20.0 + gnd_grid_buffer_size: 4 + detection_range_z_max: 2.5 + elevation_grid_mode: true + low_priority_region_x: -20.0 + center_pcl_shift: 0.0 + radial_divider_angle_deg: 1.0 + use_recheck_ground_cluster: true + use_lowest_point: true diff --git a/edge_auto_launch/launch/component/hesai_pandar_xt32.launch.xml b/edge_auto_launch/launch/component/hesai_pandar_xt32.launch.xml index f63b2c5..ce1fe72 100755 --- a/edge_auto_launch/launch/component/hesai_pandar_xt32.launch.xml +++ b/edge_auto_launch/launch/component/hesai_pandar_xt32.launch.xml @@ -23,6 +23,7 @@ + @@ -50,6 +51,9 @@ + + + diff --git a/edge_auto_launch/launch/component/roi_cluster_fusion.launch.xml b/edge_auto_launch/launch/component/roi_cluster_fusion.launch.xml index 1f4a916..22d1c08 100644 --- a/edge_auto_launch/launch/component/roi_cluster_fusion.launch.xml +++ b/edge_auto_launch/launch/component/roi_cluster_fusion.launch.xml @@ -8,8 +8,7 @@ - - + @@ -20,23 +19,12 @@ - + + - - - - - - - - - - - - diff --git a/edge_auto_launch/launch/component/voxel_grid_based_euclidean_cluster.launch.xml b/edge_auto_launch/launch/component/voxel_grid_based_euclidean_cluster.launch.xml index 0755265..740b2f4 100644 --- a/edge_auto_launch/launch/component/voxel_grid_based_euclidean_cluster.launch.xml +++ b/edge_auto_launch/launch/component/voxel_grid_based_euclidean_cluster.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/edge_auto_launch/launch/perception_xt32_sample.launch.xml b/edge_auto_launch/launch/perception_xt32_sample.launch.xml index d0b4320..f651be1 100755 --- a/edge_auto_launch/launch/perception_xt32_sample.launch.xml +++ b/edge_auto_launch/launch/perception_xt32_sample.launch.xml @@ -7,7 +7,7 @@ - + @@ -60,7 +60,7 @@ - + @@ -78,12 +78,12 @@ - + - +