Skip to content

Commit

Permalink
fix: recheck out of range and change default param
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen committed Jul 7, 2022
1 parent 1065e40 commit faab2b6
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ def get_vehicle_info(self):
p["max_longitudinal_offset"] = p["front_overhang"] + p["wheel_base"]
p["min_lateral_offset"] = -(p["wheel_tread"] / 2.0 + p["right_overhang"])
p["max_lateral_offset"] = p["wheel_tread"] / 2.0 + p["left_overhang"]
p["min_height_offset"] = -0.5
p["min_height_offset"] = -2.0
p["max_height_offset"] = p["vehicle_height"]
return p

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,8 +175,9 @@ void ScanGroundFilterComponent::classifyPointCloud(
float global_slope = std::atan2(p->orig_point->z, p->radius);
// check points which is far enough from previous point
if (
(height_from_gnd < minimum_detection_range_) ||
((p->orig_point->z - ground_cluster.getAverageHeight()) < minimum_detection_range_) ||
((p->orig_point->z < 0.0) &&
((height_from_gnd < minimum_detection_range_) ||
(p->orig_point->z - ground_cluster.getAverageHeight() < minimum_detection_range_))) ||
(height_from_gnd > maximum_detection_range_)) {
// exclude pcl under ground or higher than limit
p->point_state = PointLabel::OUT_OF_RANGE;
Expand Down

0 comments on commit faab2b6

Please sign in to comment.