Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(ground_filter): expand range of cropped_box_filter #1241

Closed
Closed
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter

std::string base_frame_;
std::string sensor_frame_;
float non_ground_heigh_thresh_ = 2.5f; // maximum height of non_ground object from ground
miursh marked this conversation as resolved.
Show resolved Hide resolved
double global_slope_max_angle_rad_; // radians
double local_slope_max_angle_rad_; // radians
double radial_divider_angle_rad_; // distance in rads between dividers
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
// set initial parameters
{
base_frame_ = declare_parameter("base_frame", "base_link");
non_ground_heigh_thresh_ =
static_cast<float>(declare_parameter("non_ground_heigh_thresh", 2.5));
global_slope_max_angle_rad_ = deg2rad(declare_parameter("global_slope_max_angle_deg", 8.0));
local_slope_max_angle_rad_ = deg2rad(declare_parameter("local_slope_max_angle_deg", 6.0));
radial_divider_angle_rad_ = deg2rad(declare_parameter("radial_divider_angle_deg", 1.0));
Expand Down Expand Up @@ -168,7 +170,13 @@ void ScanGroundFilterComponent::classifyPointCloud(

float global_slope = std::atan2(p->orig_point->z, p->radius);
// check points which is far enough from previous point
if (global_slope > global_slope_max_angle) {
if (
(height_from_gnd < -split_height_distance_) ||
miursh marked this conversation as resolved.
Show resolved Hide resolved
((p->orig_point->z - ground_cluster.getAverageHeight()) < -split_height_distance_) ||
(height_from_gnd > non_ground_heigh_thresh_)) {
// exclude pcl under ground or higher than limit
calculate_slope = false;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In this case, what would be the label for point?

Copy link
Contributor Author

@badai-nguyen badai-nguyen Jul 7, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I assigned as out_of_range label for that points

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When the point is labeled out of range, prev point label will be also set to out of range. Is this okay for next point judgement?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

as this condition , if the point is labeled out of range, the next point should not classify as POINT_FOLLOW, but GROUND, NON_GROUND or OUT_OF_RANGE.
Keeping to use the current ground_cluster and non_ground_cluster to check the next point is reasonable, IMO.

} else if (global_slope > global_slope_max_angle) {
p->point_state = PointLabel::NON_GROUND;
calculate_slope = false;
} else if (
Expand Down