Skip to content

Commit

Permalink
feat: detected object validation (tier4#507)
Browse files Browse the repository at this point in the history
  • Loading branch information
yukkysaito authored and boyali committed Oct 3, 2022
1 parent 4ee2909 commit c58ee73
Show file tree
Hide file tree
Showing 6 changed files with 53 additions and 35 deletions.
29 changes: 4 additions & 25 deletions perception/detected_object_validation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,6 @@ find_package(ament_cmake_auto REQUIRED)
### Find OpenCV Dependencies
find_package(OpenCV REQUIRED)

### Find PCL Dependencies
find_package(PCL REQUIRED QUIET COMPONENTS common search filters segmentation)

### Find Eigen Dependencies
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
Expand All @@ -36,11 +33,9 @@ include_directories(
include
SYSTEM
${OpenCV_INCLUDE_DIRS}
${PCL_COMMON_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)

# Generate occupancy grid based validator exe file
# Generate exe file
set(OCCUPANCY_GRID_BASED_VALIDATOR_SRC
src/occupancy_grid_based_validator.cpp
)
Expand All @@ -54,25 +49,9 @@ target_link_libraries(occupancy_grid_based_validator
Eigen3::Eigen
)


# Generate obstacle pointcloud based validator exe file
set(OBSTACLE_POINTCLOUD_BASED_VALIDATOR_SRC
src/obstacle_pointcloud_based_validator.cpp
)

ament_auto_add_library(obstacle_pointcloud_based_validator SHARED
${OBSTACLE_POINTCLOUD_BASED_VALIDATOR_SRC}
)

target_link_libraries(obstacle_pointcloud_based_validator
${PCL_LIBRARIES}
Eigen3::Eigen
)


rclcpp_components_register_node(obstacle_pointcloud_based_validator
PLUGIN "obstacle_pointcloud_based_validator::ObstaclePointCloudBasedValidator"
EXECUTABLE obstacle_pointcloud_based_validator_node
rclcpp_components_register_node(occupancy_grid_based_validator
PLUGIN "occupancy_grid_based_validator::OccupancyGridBasedValidator"
EXECUTABLE occupancy_grid_based_validator_node
)

if(BUILD_TESTING)
Expand Down
48 changes: 44 additions & 4 deletions perception/detected_object_validation/README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,50 @@
# detected_object_validation
# detected_object_validation (occupancy grid based validator)

## Purpose

The purpose of this package is to eliminate obvious false positives of DetectedObjects.

## References/External links
## Inner-workings / Algorithms

- [Obstacle pointcloud based validator](obstacle-pointcloud-based-validator.md)
- [Occupancy grid based validator](occupancy-grid-based-validator.md)
Compare the occupancy grid map with the DetectedObject, and if a larger percentage of obstacles are in freespace, delete them.

![debug sample image](image/debug_image.png)

Basically, it takes an occupancy grid map as input and generates a binary image of freespace or other.

A mask image is generated for each DetectedObject and the average value (percentage) in the mask image is calculated.
If the percentage is low, it is deleted.

## Inputs / Outputs

### Input

| Name | Type | Description |
| ---------------------------- | ----------------------------------------------------- | ----------------------------------------------------------- |
| `~/input/detected_objects` | `autoware_auto_perception_msgs::msg::DetectedObjects` | DetectedObjects |
| `~/input/occupancy_grid_map` | `nav_msgs::msg::OccupancyGrid` | OccupancyGrid with no time series calculation is preferred. |

### Output

| Name | Type | Description |
| ------------------ | ----------------------------------------------------- | ------------------------- |
| `~/output/objects` | `autoware_auto_perception_msgs::msg::DetectedObjects` | validated DetectedObjects |

## Parameters

| Name | Type | Description |
| ---------------- | ----- | -------------------------------------------------- |
| `mean_threshold` | float | The percentage threshold of allowed non-freespace. |
| `enable_debug` | bool | Whether to display debug images or not? |

## Assumptions / Known limits

Currently, only vehicle represented as BoundingBox are supported.

## (Optional) Error detection and handling

## (Optional) Performance characterization

## (Optional) References/External links

## (Optional) Future extensions / Unimplemented parts
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,14 @@

<launch>
<arg name="input/detected_objects" default="/perception/object_recognition/detection/objects" />
<arg name="output/objects" default="/perception/object_recognition/detection/validation/occupancy_grid_based/objects" />
<arg name="output/objects" default="/perception/object_recognition/detection/validattion/occupancy_grid_based/objects" />

<arg name="input/laserscan" default="/perception/occupancy_grid_map/virtual_scan/laserscan" />
<arg name="input/lasescan" default="/perception/occupancy_grid_map/virtual_scan/laserscan" />
<arg name="input/occupancy_grid_map" default="/perception/object_recognition/detection/validation/occupancy_grid_based/single_frame_occupancy_grid_map" />


<node pkg="laserscan_to_occupancy_grid_map" exec="laserscan_to_occupancy_grid_map_node" name="single_frame_laserscan_occupancy_grid_map" output="screen">
<remap from="~/input/laserscan" to="$(var input/laserscan)" />
<remap from="~/input/laserscan" to="/perception/occupancy_grid_map/virtual_scan/laserscan" />
<remap from="~/output/occupancy_grid_map" to="$(var input/occupancy_grid_map)" />
<param name="input_obstacle_pointcloud" value="false" />
<param name="input_obstacle_and_raw_pointcloud" value="false" />
Expand Down
1 change: 0 additions & 1 deletion perception/detected_object_validation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
<depend>autoware_auto_perception_msgs</depend>
<depend>message_filters</depend>
<depend>nav_msgs</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -213,10 +213,10 @@ void OccupancyGridBasedValidator::toPolygon2d(
vertices.push_back(cv::Point2f(pose.position.x + offset3.x(), pose.position.y + offset3.y()));
} else if (object.shape.type == Shape::CYLINDER) {
RCLCPP_WARN_THROTTLE(
this->get_logger(), *this->get_clock(), 5000, "CYLINDER type is not supported");
this->get_logger(), *this->get_clock(), 5, "CYLINDER type is not supported");
} else if (object.shape.type == Shape::POLYGON) {
RCLCPP_WARN_THROTTLE(
this->get_logger(), *this->get_clock(), 5000, "POLYGON type is not supported");
this->get_logger(), *this->get_clock(), 5, "POLYGON type is not supported");
}
}

Expand Down

0 comments on commit c58ee73

Please sign in to comment.