diff --git a/planning/behavior_velocity_intersection_module/CMakeLists.txt b/planning/behavior_velocity_intersection_module/CMakeLists.txt
index 3e6d5bc81ff92..8ff78dac06716 100644
--- a/planning/behavior_velocity_intersection_module/CMakeLists.txt
+++ b/planning/behavior_velocity_intersection_module/CMakeLists.txt
@@ -5,6 +5,8 @@ find_package(autoware_cmake REQUIRED)
autoware_package()
pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml)
+find_package(OpenCV REQUIRED)
+
ament_auto_add_library(${PROJECT_NAME} SHARED
src/debug.cpp
src/manager.cpp
@@ -13,4 +15,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
src/util.cpp
)
+target_link_libraries(${PROJECT_NAME}
+ ${OpenCV_LIBRARIES}
+)
+
ament_auto_package(INSTALL_TO_SHARE config)
diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml
index efe0efa3d7310..cbd4d4879753b 100644
--- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml
+++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml
@@ -46,7 +46,7 @@
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]
- pub_debug_grid: false
+ possible_object_bbox: [1.0, 2.0] # [m x m]
enable_rtc: # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
intersection: true
diff --git a/planning/behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_intersection_module/package.xml
index 25df9f2385d74..1d6067d4be322 100644
--- a/planning/behavior_velocity_intersection_module/package.xml
+++ b/planning/behavior_velocity_intersection_module/package.xml
@@ -20,14 +20,9 @@
autoware_auto_perception_msgs
autoware_auto_planning_msgs
behavior_velocity_planner_common
- cv_bridge
geometry_msgs
- grid_map_cv
- grid_map_ros
interpolation
lanelet2_extension
- libboost-dev
- libopencv-dev
magic_enum
motion_utils
nav_msgs
diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp
index f0602a7bcce4c..336087751d9aa 100644
--- a/planning/behavior_velocity_intersection_module/src/manager.cpp
+++ b/planning/behavior_velocity_intersection_module/src/manager.cpp
@@ -113,7 +113,6 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
ip.occlusion.max_vehicle_velocity_for_rss =
node.declare_parameter(ns + ".occlusion.max_vehicle_velocity_for_rss");
ip.occlusion.denoise_kernel = node.declare_parameter(ns + ".occlusion.denoise_kernel");
- ip.occlusion.pub_debug_grid = node.declare_parameter(ns + ".occlusion.pub_debug_grid");
ip.occlusion.possible_object_bbox =
node.declare_parameter>(ns + ".occlusion.possible_object_bbox");
}
diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
index c52d51637e0ac..d4db6e83861a2 100644
--- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
+++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
@@ -12,34 +12,20 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include
-#include
-#include
-#include
-#include
-#include
-
-#if __has_include()
-#include
-#else
-#include
-#endif
-// #include
-// #include
#include "scene_intersection.hpp"
+
#include "util.hpp"
#include
#include
#include
+#include
+#include
+#include
+#include
#include
#include
-#include
-#include
-#include
-#include
-
#include
#include
@@ -49,8 +35,6 @@
#include
#include
-BOOST_GEOMETRY_REGISTER_POINT_2D(cv::Point, int, cs::cartesian, x, y) // NOLINT
-
namespace behavior_velocity_planner
{
namespace bg = boost::geometry;
@@ -100,10 +84,6 @@ IntersectionModule::IntersectionModule(
planner_param_.collision_detection.state_transit_margin_time);
before_creep_state_machine_.setMarginTime(planner_param_.occlusion.before_creep_stop_time);
before_creep_state_machine_.setState(StateMachine::State::STOP);
- if (enable_occlusion_detection) {
- occlusion_grid_pub_ = node_.create_publisher(
- "~/debug/intersection/occlusion_grid", rclcpp::QoS(1).transient_local());
- }
stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area);
stuck_private_area_timeout_.setState(StateMachine::State::STOP);
}
@@ -1111,9 +1091,6 @@ bool IntersectionModule::checkCollision(
return collision_detected;
}
-using CvPolygon = boost::geometry::model::polygon;
-using CvLineString = boost::geometry::model::linestring;
-
bool IntersectionModule::isOcclusionCleared(
const nav_msgs::msg::OccupancyGrid & occ_grid,
const std::vector & attention_areas,
@@ -1355,10 +1332,20 @@ bool IntersectionModule::isOcclusionCleared(
cv::findContours(occlusion_mask, contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_SIMPLE);
std::vector> valid_contours;
for (const auto & contour : contours) {
+ std::vector valid_contour;
+ for (const auto & p : contour) {
+ if (distance_grid.at(p.y, p.x) == undef_pixel) {
+ continue;
+ }
+ valid_contour.push_back(p);
+ }
+ if (valid_contour.size() <= 2) {
+ continue;
+ }
std::vector approx_contour;
cv::approxPolyDP(
- contour, approx_contour,
- std::round(std::min(possible_object_bbox_x, possible_object_bbox_y) / resolution), true);
+ valid_contour, approx_contour,
+ std::round(std::min(possible_object_bbox_x, possible_object_bbox_y) / std::sqrt(2.0)), true);
if (approx_contour.size() <= 1) continue;
// check area
const double poly_area = cv::contourArea(approx_contour);
@@ -1378,59 +1365,29 @@ bool IntersectionModule::isOcclusionCleared(
debug_data_.occlusion_polygons.push_back(polygon_msg);
}
- // clean-up and find nearest risk
const int min_cost_thr = dist2pixel(occlusion_dist_thr);
int min_cost = undef_pixel - 1;
- int max_cost = 0;
- std::optional min_cost_projection_ind = std::nullopt;
geometry_msgs::msg::Point nearest_occlusion_point;
- for (int i = 0; i < width; ++i) {
- for (int j = 0; j < height; ++j) {
- const int pixel = static_cast(distance_grid.at(height - 1 - j, i));
- const bool occluded = (occlusion_mask.at(height - 1 - j, i) == 255);
+ for (const auto & occlusion_contour : valid_contours) {
+ for (const auto & p : occlusion_contour) {
+ const int pixel = static_cast(distance_grid.at(p.y, p.x));
+ const bool occluded = (occlusion_mask.at(p.y, p.x) == 255);
if (pixel == undef_pixel || !occluded) {
- // ignore outside of cropped
- // some cell maybe undef still
- distance_grid.at(height - 1 - j, i) = 0;
continue;
}
- if (max_cost < pixel) {
- max_cost = pixel;
- }
- const int projection_ind = projection_ind_grid.at(height - 1 - j, i);
if (pixel < min_cost) {
- assert(projection_ind >= 0);
min_cost = pixel;
- min_cost_projection_ind = projection_ind;
- nearest_occlusion_point.x = origin.x + i * resolution;
- nearest_occlusion_point.y = origin.y + j * resolution;
- nearest_occlusion_point.z = origin.z + distance_max * pixel / max_cost_pixel;
+ nearest_occlusion_point.x = origin.x + p.x * resolution;
+ nearest_occlusion_point.y = origin.y + (height - 1 - p.y) * resolution;
+ nearest_occlusion_point.z = origin.z;
}
}
}
- debug_data_.nearest_occlusion_point = nearest_occlusion_point;
-
- if (planner_param_.occlusion.pub_debug_grid) {
- cv::Mat distance_grid_heatmap;
- cv::applyColorMap(distance_grid, distance_grid_heatmap, cv::COLORMAP_JET);
- grid_map::GridMap occlusion_grid({"elevation"});
- occlusion_grid.setFrameId("map");
- occlusion_grid.setGeometry(
- grid_map::Length(width * resolution, height * resolution), resolution,
- grid_map::Position(origin.x + width * resolution / 2, origin.y + height * resolution / 2));
- cv::rotate(distance_grid, distance_grid, cv::ROTATE_90_COUNTERCLOCKWISE);
- cv::rotate(distance_grid_heatmap, distance_grid_heatmap, cv::ROTATE_90_COUNTERCLOCKWISE);
- grid_map::GridMapCvConverter::addLayerFromImage(
- distance_grid, "elevation", occlusion_grid, origin.z /* elevation for 0 */,
- origin.z + distance_max /* elevation for 255 */);
- grid_map::GridMapCvConverter::addColorLayerFromImage(
- distance_grid_heatmap, "color", occlusion_grid);
- occlusion_grid_pub_->publish(grid_map::GridMapRosConverter::toMessage(occlusion_grid));
- }
- if (min_cost > min_cost_thr || !min_cost_projection_ind.has_value()) {
+ if (min_cost > min_cost_thr) {
return true;
} else {
+ debug_data_.nearest_occlusion_point = nearest_occlusion_point;
return false;
}
}
diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp
index dd544b10a8e77..950cd6006cbe4 100644
--- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp
+++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp
@@ -20,13 +20,11 @@
#include
#include
#include
-#include
#include
#include
#include
#include
-#include
#include
#include
@@ -108,7 +106,6 @@ class IntersectionModule : public SceneModuleInterface
double min_vehicle_brake_for_rss;
double max_vehicle_velocity_for_rss;
double denoise_kernel;
- bool pub_debug_grid;
std::vector possible_object_bbox;
} occlusion;
};
@@ -275,7 +272,6 @@ class IntersectionModule : public SceneModuleInterface
*/
util::DebugData debug_data_;
- rclcpp::Publisher::SharedPtr occlusion_grid_pub_;
};
} // namespace behavior_velocity_planner