Package Summary
Tags | No category tags. |
Version | 1.0.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2024-09-19 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Kotaro Uetake
Authors
- Kotaro Uetake
heatmap_visualizer
Purpose
heatmap_visualizer is a package for visualizing heatmap of detected 3D objects’ positions on the BEV space.
This package is used for qualitative evaluation and trend analysis of the detector, it means, for instance, the heatmap shows “This detector performs good for near around of our vehicle, but far is bad”.
How to run
ros2 launch heatmap_visualizer heatmap_visualizer.launch.xml input/objects:=<DETECTED_OBJECTS_TOPIC>
Inner-workings / Algorithms
In this implementation, create heatmap of the center position of detected objects for each classes, for instance, CAR, PEDESTRIAN, etc, and publish them as occupancy grid maps.
In the above figure, the pink represents high detection frequency area and blue one is low, or black represents there is no detection.
As inner-workings, add center positions of detected objects to index of each corresponding grid map cell in a buffer.
The created heatmap will be published by each specific frame, which can be specified with frame_count
. Note that the buffer to be add the positions is not reset per publishing.
When publishing, firstly these values are normalized to [0, 1] using maximum and minimum values in the buffer. Secondly, they are scaled to integer in [0, 100] because nav_msgs::msg::OccupancyGrid
only allow the value in [0, 100].
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/objects |
autoware_auto_perception_msgs::msg::DetectedObjects |
detected objects |
Output
Name | Type | Description |
---|---|---|
~/output/objects/<CLASS_NAME> |
nav_msgs::msg::OccupancyGrid |
visualized heatmap |
Parameters
Core Parameters
Name | Type | Default Value | Description |
---|---|---|---|
publish_frame_count |
int | 50 |
The number of frames to publish heatmap |
heatmap_frame_id |
string | base_link |
The frame ID of heatmap to be respected |
heatmap_length |
float | 200.0 |
A length of map in meter |
heatmap_resolution |
float | 0.8 |
A resolution of map |
use_confidence |
bool | false |
A flag if use confidence score as heatmap value |
class_names |
array |
["UNKNOWN", "CAR", "TRUCK", "BUS", "TRAILER", "BICYCLE", "MOTORBIKE", "PEDESTRIAN"] |
An array of class names to be published |
rename_to_car |
bool | true |
A flag if rename car like vehicle to car |
Assumptions / Known limits
The heatmap depends on the data to be used, so if the objects in data are sparse the heatmap will be sparse.
(Optional) Error detection and handling
(Optional) Performance characterization
References/External links
(Optional) Future extensions / Unimplemented parts
Wiki Tutorials
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/heatmap_visualizer.launch.xml
-
- input/objects [default: objects]
- config_file [default: $(find-pkg-share heatmap_visualizer)/config/heatmap_visualizer.param.yaml]