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

feat(intersection): denoise occlusion by morphology open process #3763

Merged
merged 3 commits into from
May 19, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
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 @@ -40,6 +40,7 @@
before_creep_stop_time: 1.0 # [s]
min_vehicle_brake_for_rss: -2.5 # [m/s^2]
max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph
denoise_kernel: 1.0 # [m]

merge_from_private:
stop_duration_sec: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ class IntersectionModule : public SceneModuleInterface
double before_creep_stop_time;
double min_vehicle_brake_for_rss;
double max_vehicle_velocity_for_rss;
double denoise_kernel;
} occlusion;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,7 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
node.declare_parameter<double>(ns + ".occlusion.min_vehicle_brake_for_rss");
ip.occlusion.max_vehicle_velocity_for_rss =
node.declare_parameter<double>(ns + ".occlusion.max_vehicle_velocity_for_rss");
ip.occlusion.denoise_kernel = node.declare_parameter<double>(ns + ".occlusion.denoise_kernel");
}

void IntersectionModuleManager::launchNewModules(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1070,8 +1070,14 @@ bool IntersectionModule::isOcclusionCleared(
}

// (3) occlusion mask
cv::Mat occlusion_mask(width, height, CV_8UC1, cv::Scalar(0));
cv::bitwise_and(detection_mask, unknown_mask, occlusion_mask);
cv::Mat occlusion_mask_raw(width, height, CV_8UC1, cv::Scalar(0));
cv::bitwise_and(detection_mask, unknown_mask, occlusion_mask_raw);
// (3.1) apply morphologyEx
cv::Mat occlusion_mask;
const int morph_size = std::ceil(planner_param_.occlusion.denoise_kernel / reso);
cv::morphologyEx(
occlusion_mask_raw, occlusion_mask, cv::MORPH_OPEN,
cv::getStructuringElement(cv::MORPH_RECT, cv::Size(morph_size, morph_size)));

// (4) create distance grid
// value: 0 - 254: signed distance representing [distamce_min, distance_max]
Expand Down