Skip to content

Commit

Permalink
feat(perception_evaluator): counts objects within detection range (#6848
Browse files Browse the repository at this point in the history
)

* feat(perception_evaluator): counts objects within detection range

Signed-off-by: kosuke55 <[email protected]>

detection counter

Signed-off-by: kosuke55 <[email protected]>

add enable option and refactoring

Signed-off-by: kosuke55 <[email protected]>

fix

update document

Signed-off-by: kosuke55 <[email protected]>

readme

Signed-off-by: kosuke55 <[email protected]>

clean up

Signed-off-by: kosuke55 <[email protected]>

* fix from review

Signed-off-by: kosuke55 <[email protected]>

* use $

Signed-off-by: kosuke55 <[email protected]>

fix

Signed-off-by: kosuke55 <[email protected]>

* fix include

Signed-off-by: kosuke55 <[email protected]>

---------

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 authored Apr 24, 2024
1 parent 8881d23 commit 6459816
Show file tree
Hide file tree
Showing 15 changed files with 1,697 additions and 191 deletions.
3 changes: 2 additions & 1 deletion evaluator/perception_online_evaluator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME}_node SHARED
src/metrics_calculator.cpp
src/${PROJECT_NAME}_node.cpp
src/metrics/deviation_metrics.cpp
src/metrics/detection_count.cpp
src/utils/marker_utils.cpp
src/utils/objects_filtering.cpp
)
Expand All @@ -31,7 +32,7 @@ target_link_libraries(${PROJECT_NAME}_node glog::glog)
if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
test/test_perception_online_evaluator_node.cpp
TIMEOUT 180
TIMEOUT 300
)
target_link_libraries(test_${PROJECT_NAME}
${PROJECT_NAME}_node
Expand Down
90 changes: 82 additions & 8 deletions evaluator/perception_online_evaluator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,9 @@ The evaluated metrics are as follows:
- lateral_deviation
- yaw_deviation
- yaw_rate
- total_objects_count
- average_objects_count
- interval_objects_count

### Predicted Path Deviation / Predicted Path Deviation Variance

Expand Down Expand Up @@ -89,6 +92,67 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p

![yaw_rate](./images/yaw_rate.drawio.svg)

### Object Counts

Counts the number of detections for each object class within the specified detection range. These metrics are measured for the most recent object not past objects.

![detection_counts](./images/detection_counts.drawio.svg)

In the provided illustration, the range $R$ is determined by a combination of lists of radii (e.g., $r_1, r_2, \ldots$) and heights (e.g., $h_1, h_2, \ldots$).
For example,

- the number of CAR in range $R = (r_1, h_1)$ equals 1
- the number of CAR in range $R = (r_1, h_2)$ equals 2
- the number of CAR in range $R = (r_2, h_1)$ equals 3
- the number of CAR in range $R = (r_2, h_2)$ equals 4

#### Total Object Count

Counts the number of unique objects for each class within the specified detection range. The total object count is calculated as follows:

$$
\begin{align}
\text{Total Object Count (Class, Range)} = \left| \bigcup_{t=0}^{T_{\text{now}}} \{ \text{uuid} \mid \text{class}(t, \text{uuid}) = C \wedge \text{position}(t, \text{uuid}) \in R \} \right|
\end{align}
$$

where:

- $\bigcup$ represents the union across all frames from $t = 0$ to $T_{\text{now}}$, which ensures that each uuid is counted only once.
- $\text{class}(t, \text{uuid}) = C$ specifies that the object with uuid at time $t$ belongs to class $C$.
- $\text{position}(t, \text{uuid}) \in R$ indicates that the object with uuid at time $t$ is within the specified range $R$.
- $\left| \{ \ldots \} \right|$ denotes the cardinality of the set, which counts the number of unique uuids that meet the class and range criteria across all considered times.

#### Average Object Count

Counts the average number of objects for each class within the specified detection range. This metric measures how many objects were detected in one frame, without considering uuids. The average object count is calculated as follows:

$$
\begin{align}
\text{Average Object Count (Class, Range)} = \frac{1}{N} \sum_{t=0}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right|
\end{align}
$$

where:

- $N$ represents the total number of frames within the time period time to $T\_{\text{now}}$ (it is precisely `detection_count_purge_seconds`)
- $text{object}$ denotes the number of objects that meet the class and range criteria at time $t$.

#### Interval Object Count

Counts the average number of objects for each class within the specified detection range over the last `objects_count_window_seconds`. This metric measures how many objects were detected in one frame, without considering uuids. The interval object count is calculated as follows:

$$
\begin{align}
\text{Interval Object Count (Class, Range)} = \frac{1}{W} \sum_{t=T_{\text{now}} - T_W}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right|
\end{align}
$$

where:

- $W$ represents the total number of frames within the last `objects_count_window_seconds`.
- $T_W$ represents the time window `objects_count_window_seconds`

## Inputs / Outputs

| Name | Type | Description |
Expand All @@ -99,14 +163,24 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p

## Parameters

| Name | Type | Description |
| --------------------------------- | ------------ | ------------------------------------------------------------------------------------------------ |
| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. |
| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. |
| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. |
| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped |
| `target_object.*.check_deviation` | bool | Whether to check deviation for specific object types (car, truck, etc.). |
| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). |
| Name | Type | Description |
| ------------------------------------------------------ | ------------ | ----------------------------------------------------------------------------------------------------------------------------------------------- |
| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. |
| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. |
| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. |
| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped |
| `detection_radius_list` | list[double] | Detection radius for objects to be evaluated.(used for objects count only) |
| `detection_height_list` | list[double] | Detection height for objects to be evaluated. (used for objects count only) |
| `detection_count_purge_seconds` | double | Time window for purging object detection counts. |
| `objects_count_window_seconds` | double | Time window for keeping object detection counts. The number of object detections within this time window is stored in `detection_count_vector_` |
| `target_object.*.check_lateral_deviation` | bool | Whether to check lateral deviation for specific object types (car, truck, etc.). |
| `target_object.*.check_yaw_deviation` | bool | Whether to check yaw deviation for specific object types (car, truck, etc.). |
| `target_object.*.check_predicted_path_deviation` | bool | Whether to check predicted path deviation for specific object types (car, truck, etc.). |
| `target_object.*.check_yaw_rate` | bool | Whether to check yaw rate for specific object types (car, truck, etc.). |
| `target_object.*.check_total_objects_count` | bool | Whether to check total object count for specific object types (car, truck, etc.). |
| `target_object.*.check_average_objects_count` | bool | Whether to check average object count for specific object types (car, truck, etc.). |
| `target_object.*.check_interval_average_objects_count` | bool | Whether to check interval average object count for specific object types (car, truck, etc.). |
| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). |

## Assumptions / Known limits

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
172 changes: 153 additions & 19 deletions evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg
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
@@ -0,0 +1,149 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_

#include "perception_online_evaluator/parameters.hpp"
#include "perception_online_evaluator/stat.hpp"
#include "tf2_ros/buffer.h"

#include <rclcpp/rclcpp.hpp>

#include "autoware_auto_perception_msgs/msg/object_classification.hpp"
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
#include <geometry_msgs/msg/pose.hpp>

#include <iomanip>
#include <memory>
#include <set>
#include <sstream>
#include <string>
#include <unordered_map>
#include <vector>

namespace perception_diagnostics
{
namespace metrics
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObjects;

struct DetectionRange
{
double radius;
double height;

DetectionRange(double radius, double height) : radius(radius), height(height) {}

std::string toString() const
{
std::ostringstream oss;
oss << std::fixed << std::setprecision(2);
oss << "r" << radius << "_h" << height;
return oss.str();
}
};
using DetectionRanges = std::vector<DetectionRange>;

/*
* @brief Class to count objects detected within a certain range for each class
* The overall frame is not eternal, and data older than the purge seconds is deleted to prevent
memory bloat.
1. Count the total number of unique objects detected across the overall frame. Data older than the
purge seconds is deleted to prevent memory bloat.
2. Calculate the average number of objects detected in each frame across the overall frame.
3. Calculate the average number of objects detected in each frame within a certain time frame.
*/
class DetectionCounter
{
public:
/*
* @brief Constructor
* @param parameters Parameters for the perception online evaluator
*/
explicit DetectionCounter(const std::shared_ptr<Parameters> & parameters)
: parameters_(parameters)
{
}
/*
* @brief Add objects to the detection counter
* @param objects Predicted objects
* @param tf_buffer tf2 buffer for transforming object poses
*/
void addObjects(const PredictedObjects & objects, const tf2_ros::Buffer & tf_buffer);

/*
* @brief Get the average count of objects detected in the last `seconds` seconds
* @param seconds Time window in seconds
* @return Map of classification to range to average count
*/
std::unordered_map<std::uint8_t, std::unordered_map<std::string, double>> getAverageCount(
double seconds) const;

/*
* @brief Get the overall average count of objects detected
* @return Map of classification to range to average count
*/
std::unordered_map<std::uint8_t, std::unordered_map<std::string, double>> getOverallAverageCount()
const;

/*
* @brief Get the total count of objects detected
* @return Map of classification to range to total count
*/
std::unordered_map<std::uint8_t, std::unordered_map<std::string, size_t>> getTotalCount() const;

private:
/*
* @brief Initialize the detection map
*/
void initializeDetectionMap();

/*
* @brief Update the detection map with a new detection
* @param uuid UUID of the detected object
* @param classification Classification of the detected object
* @param range Range of the detected object
* @param timestamp Timestamp of the detection
*/
void updateDetectionMap(
const std::string uuid, const std::uint8_t classification, const std::string & range,
const rclcpp::Time & timestamp);

/*
* @brief Purge old records from the detection map
* @param current_time Current time
*/
void purgeOldRecords(rclcpp::Time current_time);

/*
* @brief Get the DetectionRanges from parameters
* @return Detection ranges
*/
DetectionRanges getRanges() const;

std::shared_ptr<Parameters> parameters_;
std::set<rclcpp::Time> unique_timestamps_;

// Structures for storing detection counts and UUIDs for uniqueness checks
std::unordered_map<std::uint8_t, std::unordered_map<std::string, std::vector<rclcpp::Time>>>
time_series_counts_;
std::unordered_map<std::uint8_t, std::unordered_map<std::string, std::set<std::string>>>
seen_uuids_;
};
} // namespace metrics
} // namespace perception_diagnostics

#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ enum class Metric {
yaw_deviation,
predicted_path_deviation,
yaw_rate,
objects_count,
SIZE,
};

Expand All @@ -47,20 +48,23 @@ static const std::unordered_map<std::string, Metric> str_to_metric = {
{"lateral_deviation", Metric::lateral_deviation},
{"yaw_deviation", Metric::yaw_deviation},
{"predicted_path_deviation", Metric::predicted_path_deviation},
{"yaw_rate", Metric::yaw_rate}};
{"yaw_rate", Metric::yaw_rate},
{"objects_count", Metric::objects_count}};

static const std::unordered_map<Metric, std::string> metric_to_str = {
{Metric::lateral_deviation, "lateral_deviation"},
{Metric::yaw_deviation, "yaw_deviation"},
{Metric::predicted_path_deviation, "predicted_path_deviation"},
{Metric::yaw_rate, "yaw_rate"}};
{Metric::yaw_rate, "yaw_rate"},
{Metric::objects_count, "objects_count"}};

// Metrics descriptions
static const std::unordered_map<Metric, std::string> metric_descriptions = {
{Metric::lateral_deviation, "Lateral_deviation[m]"},
{Metric::yaw_deviation, "Yaw_deviation[rad]"},
{Metric::predicted_path_deviation, "Predicted_path_deviation[m]"},
{Metric::yaw_rate, "Yaw_rate[rad/s]"}};
{Metric::yaw_rate, "Yaw_rate[rad/s]"},
{Metric::objects_count, "objects_count"}};

namespace details
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,21 +15,27 @@
#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_

#include "perception_online_evaluator/metrics/detection_count.hpp"
#include "perception_online_evaluator/metrics/deviation_metrics.hpp"
#include "perception_online_evaluator/metrics/metric.hpp"
#include "perception_online_evaluator/parameters.hpp"
#include "perception_online_evaluator/stat.hpp"
#include "perception_online_evaluator/utils/objects_filtering.hpp"
#include "tf2_ros/buffer.h"

#include <rclcpp/time.hpp>

#include "autoware_auto_perception_msgs/msg/object_classification.hpp"
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include <unique_identifier_msgs/msg/uuid.hpp>

#include <algorithm>
#include <map>
#include <memory>
#include <optional>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

Expand All @@ -39,6 +45,7 @@ using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using metrics::DetectionCounter;
using unique_identifier_msgs::msg::UUID;

struct ObjectData
Expand Down Expand Up @@ -80,7 +87,9 @@ class MetricsCalculator
{
public:
explicit MetricsCalculator(const std::shared_ptr<Parameters> & parameters)
: parameters_(parameters){};
: parameters_(parameters), detection_counter_(parameters)
{
}

/**
* @brief calculate
Expand All @@ -92,8 +101,11 @@ class MetricsCalculator
/**
* @brief set the dynamic objects used to calculate obstacle metrics
* @param [in] objects predicted objects
* @param [in] tf_buffer tf buffer
*/
void setPredictedObjects(const PredictedObjects & objects);
void setPredictedObjects(const PredictedObjects & objects, const tf2_ros::Buffer & tf_buffer);

void updateObjectsCountMap(const PredictedObjects & objects, const tf2_ros::Buffer & tf_buffer);

HistoryPathMap getHistoryPathMap() const { return history_path_map_; }
ObjectDataMap getDebugObjectData() const { return debug_target_object_; }
Expand All @@ -107,6 +119,8 @@ class MetricsCalculator

rclcpp::Time current_stamp_;

DetectionCounter detection_counter_;

// debug
mutable ObjectDataMap debug_target_object_;

Expand All @@ -129,6 +143,7 @@ class MetricsCalculator
PredictedPathDeviationMetrics calcPredictedPathDeviationMetrics(
const PredictedObjects & objects, const double time_horizon) const;
MetricStatMap calcYawRateMetrics(const ClassObjectsMap & class_objects_map) const;
MetricStatMap calcObjectsCountMetrics() const;

bool hasPassedTime(const rclcpp::Time stamp) const;
bool hasPassedTime(const std::string uuid, const rclcpp::Time stamp) const;
Expand Down
Loading

0 comments on commit 6459816

Please sign in to comment.