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(perception_online_evaluator): publish metrics of each object class #6556

Merged
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 @@ -19,6 +19,7 @@
#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 <rclcpp/time.hpp>

Expand Down Expand Up @@ -118,9 +119,9 @@ class MetricsCalculator
void deleteOldObjects(const rclcpp::Time stamp);

// Calculate metrics
MetricStatMap calcLateralDeviationMetrics(const PredictedObjects & objects) const;
MetricStatMap calcYawDeviationMetrics(const PredictedObjects & objects) const;
MetricStatMap calcPredictedPathDeviationMetrics(const PredictedObjects & objects) const;
MetricStatMap calcLateralDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
MetricStatMap calcYawDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
MetricStatMap calcPredictedPathDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
Stat<double> calcPredictedPathDeviationMetrics(
const PredictedObjects & objects, const double time_horizon) const;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;

using ClassObjectsMap = std::unordered_map<uint8_t, PredictedObjects>;

std::uint8_t getHighestProbLabel(const std::vector<ObjectClassification> & classification);

/**
Expand Down Expand Up @@ -105,6 +107,14 @@ void filterObjects(PredictedObjects & objects, Func filter)
filterObjects(objects, removed_objects, filter);
}

/**
* @brief Separates the provided objects based on their classification.
*
* @param objects The predicted objects to be separated.
* @return A map of objects separated by their classification.
*/
ClassObjectsMap separateObjectsByClass(const PredictedObjects & objects);

/**
* @brief Filters the provided objects based on their classification.
*
Expand Down
1 change: 1 addition & 0 deletions evaluator/perception_online_evaluator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<depend>libgoogle-glog-dev</depend>
<depend>motion_utils</depend>
<depend>nav_msgs</depend>
<depend>object_recognition_utils</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
101 changes: 54 additions & 47 deletions evaluator/perception_online_evaluator/src/metrics_calculator.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 TIER IV, Inc.

Check notice on line 1 in evaluator/perception_online_evaluator/src/metrics_calculator.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.12 to 5.29, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -15,13 +15,15 @@
#include "perception_online_evaluator/metrics_calculator.hpp"

#include "motion_utils/trajectory/trajectory.hpp"
#include "perception_online_evaluator/utils/objects_filtering.hpp"
#include "object_recognition_utils/object_recognition_utils.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include <tier4_autoware_utils/ros/uuid_helper.hpp>

namespace perception_diagnostics
{
using object_recognition_utils::convertLabelToString;

std::optional<MetricStatMap> MetricsCalculator::calculate(const Metric & metric) const
{
if (object_map_.empty()) {
Expand All @@ -35,14 +37,14 @@
return {};
}
const auto target_objects = getObjectsByStamp(target_stamp);

const ClassObjectsMap class_objects_map = separateObjectsByClass(target_objects);
switch (metric) {
case Metric::lateral_deviation:
return calcLateralDeviationMetrics(target_objects);
return calcLateralDeviationMetrics(class_objects_map);
case Metric::yaw_deviation:
return calcYawDeviationMetrics(target_objects);
return calcYawDeviationMetrics(class_objects_map);
case Metric::predicted_path_deviation:
return calcPredictedPathDeviationMetrics(target_objects);
return calcPredictedPathDeviationMetrics(class_objects_map);
default:
return {};
}
Expand Down Expand Up @@ -155,65 +157,70 @@
return objects;
}

MetricStatMap MetricsCalculator::calcLateralDeviationMetrics(const PredictedObjects & objects) const
MetricStatMap MetricsCalculator::calcLateralDeviationMetrics(
const ClassObjectsMap & class_objects_map) const
{
Stat<double> stat{};
const auto stamp = rclcpp::Time(objects.header.stamp);

for (const auto & object : objects.objects) {
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
if (!hasPassedTime(uuid, stamp)) {
continue;
}
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
const auto history_path = history_path_map_.at(uuid).second;
if (history_path.empty()) {
continue;
MetricStatMap metric_stat_map{};
for (const auto & [label, objects] : class_objects_map) {
Stat<double> stat{};
const auto stamp = rclcpp::Time(objects.header.stamp);
for (const auto & object : objects.objects) {
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
if (!hasPassedTime(uuid, stamp)) {
continue;

Check warning on line 170 in evaluator/perception_online_evaluator/src/metrics_calculator.cpp

View check run for this annotation

Codecov / codecov/patch

evaluator/perception_online_evaluator/src/metrics_calculator.cpp#L170

Added line #L170 was not covered by tests
}
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
const auto history_path = history_path_map_.at(uuid).second;
if (history_path.empty()) {
continue;
}
stat.add(metrics::calcLateralDeviation(history_path, object_pose));
}
stat.add(metrics::calcLateralDeviation(history_path, object_pose));
metric_stat_map["lateral_deviation_" + convertLabelToString(label)] = stat;
}

MetricStatMap metric_stat_map;
metric_stat_map["lateral_deviation"] = stat;
return metric_stat_map;
}

MetricStatMap MetricsCalculator::calcYawDeviationMetrics(const PredictedObjects & objects) const
MetricStatMap MetricsCalculator::calcYawDeviationMetrics(
const ClassObjectsMap & class_objects_map) const
{
Stat<double> stat{};
const auto stamp = rclcpp::Time(objects.header.stamp);
for (const auto & object : objects.objects) {
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
if (!hasPassedTime(uuid, stamp)) {
continue;
}
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
const auto history_path = history_path_map_.at(uuid).second;
if (history_path.empty()) {
continue;
MetricStatMap metric_stat_map{};
for (const auto & [label, objects] : class_objects_map) {
Stat<double> stat{};
const auto stamp = rclcpp::Time(objects.header.stamp);
for (const auto & object : objects.objects) {
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
if (!hasPassedTime(uuid, stamp)) {
continue;

Check warning on line 194 in evaluator/perception_online_evaluator/src/metrics_calculator.cpp

View check run for this annotation

Codecov / codecov/patch

evaluator/perception_online_evaluator/src/metrics_calculator.cpp#L194

Added line #L194 was not covered by tests
}
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
const auto history_path = history_path_map_.at(uuid).second;
if (history_path.empty()) {
continue;
}
stat.add(metrics::calcYawDeviation(history_path, object_pose));
}
stat.add(metrics::calcYawDeviation(history_path, object_pose));
metric_stat_map["yaw_deviation_" + convertLabelToString(label)] = stat;
}

MetricStatMap metric_stat_map;
metric_stat_map["yaw_deviation"] = stat;
return metric_stat_map;
}

MetricStatMap MetricsCalculator::calcPredictedPathDeviationMetrics(
const PredictedObjects & objects) const
const ClassObjectsMap & class_objects_map) const
{
const auto time_horizons = parameters_->prediction_time_horizons;

MetricStatMap metric_stat_map;
for (const double time_horizon : time_horizons) {
const auto stat = calcPredictedPathDeviationMetrics(objects, time_horizon);
std::ostringstream stream;
stream << std::fixed << std::setprecision(2) << time_horizon;
std::string time_horizon_str = stream.str();
metric_stat_map["predicted_path_deviation_" + time_horizon_str] = stat;
MetricStatMap metric_stat_map{};
for (const auto & [label, objects] : class_objects_map) {
for (const double time_horizon : time_horizons) {
const auto stat = calcPredictedPathDeviationMetrics(objects, time_horizon);
std::ostringstream stream;
stream << std::fixed << std::setprecision(2) << time_horizon;
std::string time_horizon_str = stream.str();
metric_stat_map
["predicted_path_deviation_" + convertLabelToString(label) + "_" + time_horizon_str] = stat;
}
}

return metric_stat_map;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,17 @@ bool isTargetObjectType(
(t == ObjectClassification::PEDESTRIAN && target_object_types.check_pedestrian));
}

ClassObjectsMap separateObjectsByClass(const PredictedObjects & objects)
{
ClassObjectsMap separated_objects;
for (const auto & object : objects.objects) {
const auto label = getHighestProbLabel(object.classification);
separated_objects[label].objects.push_back(object);
separated_objects[label].header = objects.header;
}
return separated_objects;
}

void filterObjectsByClass(
PredictedObjects & objects, const ObjectTypesToCheck & target_object_types)
{
Expand Down
Loading
Loading