Skip to content

Commit

Permalink
chore(ground_segmentation_launch): change max_z of cropbox filter to …
Browse files Browse the repository at this point in the history
…vehicle_height (#6549)

* chore(ground_segmentation_launch): change max_z of cropbox filter to vehicle_height

Signed-off-by: badai-nguyen <[email protected]>

* fix: typo

Signed-off-by: badai-nguyen <[email protected]>

---------

Signed-off-by: badai-nguyen <[email protected]>
  • Loading branch information
badai-nguyen authored Mar 6, 2024
1 parent 9b5a372 commit 0e1761a
Showing 1 changed file with 24 additions and 0 deletions.
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,6 +96,8 @@ def create_additional_pipeline(self, lidar_name):
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
"max_z": max_z,
"min_z": min_z,
},
self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"],
],
Expand Down Expand Up @@ -206,6 +220,14 @@ 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["common_crop_box_filter"]["parameters"]["margin_max_z"]
)
min_z = (
self.vehicle_info["min_height_offset"]
+ self.ground_segmentation_param["common_crop_box_filter"]["parameters"]["margin_min_z"]
)
components = []
components.append(
ComposableNode(
Expand All @@ -220,6 +242,8 @@ def create_common_pipeline(self, input_topic, output_topic):
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
"max_z": max_z,
"min_z": min_z,
},
self.ground_segmentation_param["common_crop_box_filter"]["parameters"],
],
Expand Down

0 comments on commit 0e1761a

Please sign in to comment.