Skip to content

Commit

Permalink
chore(ground_segmentation): add missing parameters (#231)
Browse files Browse the repository at this point in the history
* chore(ground_segmentation): change parameter name

Signed-off-by: 1222-takeshi <[email protected]>

* ci(pre-commit): autofix

* Add missing params to ground_segmentation.param.yaml

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

* ci(pre-commit): autofix

* Add missing params to ground_segmentation.param.yaml

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

* Fix crop_box params in ground_segmentation.param.yaml

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

* Fix crop_box param in ground_segmentation.param.yaml

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

* Revert crop_box params

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

* Add cropbox param calc to ground_segmentation.launch.py

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

* chore(ground_segmentation): change margin_max_z for cropbox

Signed-off-by: 1222-takeshi <[email protected]>

---------

Signed-off-by: 1222-takeshi <[email protected]>
Signed-off-by: Autumn60 <[email protected]>
Co-authored-by: 1222-takeshi <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Autumn60 <[email protected]>
  • Loading branch information
4 people committed Sep 17, 2024
1 parent 5f05c26 commit e42e17b
Show file tree
Hide file tree
Showing 2 changed files with 66 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@

common_crop_box_filter:
parameters:
min_x: -100.0
max_x: 150.0
min_y: -70.0
max_y: 70.0
margin_max_z: 0.0 # to extend the crop box max_z from vehicle_height
margin_min_z: -2.5 # to extend the crop box min_z from ground
min_x: -50.0
max_x: 100.0
min_y: -50.0
max_y: 50.0
margin_max_z: 0.63 # to extend the crop box max_z from vehicle_height
margin_min_z: -0.5 # to extend the crop box min_z from ground
negative: False

common_ground_filter:
Expand All @@ -31,17 +31,26 @@
gnd_grid_buffer_size: 4
detection_range_z_max: 2.5
elevation_grid_mode: true
use_recheck_ground_cluster: true
low_priority_region_x: -20.0
center_pcl_shift: 0.0
radial_divider_angle_deg: 1.0

# common_ground_filter:
# plugin: "ground_segmentation::RayGroundFilterComponent"
# parameters:
# initial_max_slope: 10.0
# min_x: -0.01
# max_x: +0.01
# min_y: -0.01
# max_y: +0.01
# use_vehicle_footprint: True
# general_max_slope: 10.0
# local_max_slope: 10.0
# min_height_threshold: 0.3
# initial_max_slope: 10.0
# radial_divider_angle: 1.0
# min_height_threshold: 0.3
# concentric_divider_distance: 0.0
# use_vehicle_footprint: True
# reclass_distance_threshold: 0.1

short_height_obstacle_detection_area_filter:
parameters:
Expand All @@ -55,13 +64,15 @@

ransac_ground_filter:
parameters:
outlier_threshold: 0.1
min_points: 400
min_inliers: 200
# base_frame: base_link
unit_axis: "z"
max_iterations: 50
height_threshold: 0.10
min_trial: 200
min_points: 400
outlier_threshold: 0.1
plane_slope_threshold: 10.0
voxel_size_x: 0.1
voxel_size_y: 0.1
voxel_size_z: 0.1
height_threshold: 0.10
debug: False
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,18 @@ def get_vehicle_mirror_info(self):
return p

def create_additional_pipeline(self, lidar_name):
max_z = (
self.vehicle_info["max_height_offset"]
+ self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"][
"margin_max_z"
]
)
min_z = (
self.vehicle_info["min_height_offset"]
+ self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"][
"margin_min_z"
]
)
components = []
components.append(
ComposableNode(
Expand All @@ -84,8 +96,8 @@ def create_additional_pipeline(self, lidar_name):
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
# "min_z": self.vehicle_info["min_height_offset"],
# "max_z": self.vehicle_info["max_height_offset"],
"max_z": max_z,
"min_z": min_z,
},
self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"],
],
Expand Down Expand Up @@ -116,6 +128,18 @@ def create_additional_pipeline(self, lidar_name):
return components

def create_ransac_pipeline(self):
max_z = (
self.vehicle_info["max_height_offset"]
+ self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"][
"margin_max_z"
]
)
min_z = (
self.vehicle_info["min_height_offset"]
+ self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"][
"margin_min_z"
]
)
components = []
components.append(
ComposableNode(
Expand All @@ -131,6 +155,8 @@ def create_ransac_pipeline(self):
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
"max_z": max_z,
"min_z": min_z,
},
self.ground_segmentation_param["short_height_obstacle_detection_area_filter"][
"parameters"
Expand Down Expand Up @@ -184,6 +210,18 @@ def create_ransac_pipeline(self):
return components

def create_common_pipeline(self, input_topic, output_topic):
max_z = (
self.vehicle_info["max_height_offset"]
+ self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"][
"margin_max_z"
]
)
min_z = (
self.vehicle_info["min_height_offset"]
+ self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"][
"margin_min_z"
]
)
components = []
components.append(
ComposableNode(
Expand All @@ -198,8 +236,8 @@ def create_common_pipeline(self, input_topic, output_topic):
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
"min_z": self.vehicle_info["min_height_offset"],
"max_z": self.vehicle_info["max_height_offset"],
"max_z": max_z,
"min_z": min_z,
},
self.ground_segmentation_param["common_crop_box_filter"]["parameters"],
],
Expand Down

0 comments on commit e42e17b

Please sign in to comment.