Skip to content

refactor(autoware_obect_recognition_utils): rewrite using modern C++ without API breakage #396

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

Merged
merged 2 commits into from
May 9, 2025
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 @@ -31,7 +31,7 @@ namespace autoware::object_recognition_utils
{
using autoware_utils_geometry::Polygon2d;
// minimum area to avoid division by zero
static const double MIN_AREA = 1e-6;
static constexpr double MIN_AREA = 1e-6;

inline double getConvexShapeArea(const Polygon2d & source_polygon, const Polygon2d & target_polygon)
{
Expand Down Expand Up @@ -66,7 +66,8 @@ inline double getUnionArea(const Polygon2d & source_polygon, const Polygon2d & t
}

template <class T1, class T2>
double get2dIoU(const T1 source_object, const T2 target_object, const double min_union_area = 0.01)
double get2dIoU(
const T1 & source_object, const T2 & target_object, const double min_union_area = 0.01)
{
const auto source_polygon = autoware_utils_geometry::to_polygon2d(source_object);
if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0;
Expand Down Expand Up @@ -99,7 +100,7 @@ double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object)
}

template <class T1, class T2>
double get2dPrecision(const T1 source_object, const T2 target_object)
double get2dPrecision(const T1 & source_object, const T2 & target_object)
{
const auto source_polygon = autoware_utils_geometry::to_polygon2d(source_object);
const double source_area = boost::geometry::area(source_polygon);
Expand All @@ -114,7 +115,7 @@ double get2dPrecision(const T1 source_object, const T2 target_object)
}

template <class T1, class T2>
double get2dRecall(const T1 source_object, const T2 target_object)
double get2dRecall(const T1 & source_object, const T2 & target_object)
{
const auto source_polygon = autoware_utils_geometry::to_polygon2d(source_object);
if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__OBJECT_CLASSIFICATION_HPP_
#define AUTOWARE__OBJECT_RECOGNITION_UTILS__OBJECT_CLASSIFICATION_HPP_

#include "autoware_perception_msgs/msg/object_classification.hpp"
#include <autoware_perception_msgs/msg/object_classification.hpp>

#include <cstdint>
#include <string>
Expand All @@ -39,8 +39,7 @@ inline ObjectClassification getHighestProbClassification(
inline std::uint8_t getHighestProbLabel(
const std::vector<ObjectClassification> & object_classifications)
{
auto classification = getHighestProbClassification(object_classifications);
return classification.label;
return getHighestProbClassification(object_classifications).label;
}

inline bool isVehicle(const uint8_t label)
Expand All @@ -57,8 +56,7 @@ inline bool isVehicle(const ObjectClassification & object_classification)

inline bool isVehicle(const std::vector<ObjectClassification> & object_classifications)
{
auto highest_prob_label = getHighestProbLabel(object_classifications);
return isVehicle(highest_prob_label);
return isVehicle(getHighestProbLabel(object_classifications));
}

inline bool isCarLikeVehicle(const uint8_t label)
Expand All @@ -74,8 +72,7 @@ inline bool isCarLikeVehicle(const ObjectClassification & object_classification)

inline bool isCarLikeVehicle(const std::vector<ObjectClassification> & object_classifications)
{
auto highest_prob_label = getHighestProbLabel(object_classifications);
return isCarLikeVehicle(highest_prob_label);
return isCarLikeVehicle(getHighestProbLabel(object_classifications));
}

inline bool isLargeVehicle(const uint8_t label)
Expand All @@ -91,8 +88,7 @@ inline bool isLargeVehicle(const ObjectClassification & object_classification)

inline bool isLargeVehicle(const std::vector<ObjectClassification> & object_classifications)
{
auto highest_prob_label = getHighestProbLabel(object_classifications);
return isLargeVehicle(highest_prob_label);
return isLargeVehicle(getHighestProbLabel(object_classifications));
}

inline uint8_t toLabel(const std::string & class_name)
Expand Down Expand Up @@ -130,9 +126,7 @@ inline ObjectClassification toObjectClassification(
inline std::vector<ObjectClassification> toObjectClassifications(
const std::string & class_name, float probability)
{
std::vector<ObjectClassification> classifications;
classifications.push_back(toObjectClassification(class_name, probability));
return classifications;
return {toObjectClassification(class_name, probability)};
}

inline std::string convertLabelToString(const uint8_t label)
Expand All @@ -158,16 +152,15 @@ inline std::string convertLabelToString(const uint8_t label)
}
}

inline std::string convertLabelToString(const ObjectClassification object_classification)
inline std::string convertLabelToString(const ObjectClassification & object_classification)
{
return convertLabelToString(object_classification.label);
}

inline std::string convertLabelToString(
const std::vector<ObjectClassification> object_classifications)
const std::vector<ObjectClassification> & object_classifications)
{
auto highest_prob_label = getHighestProbLabel(object_classifications);
return convertLabelToString(highest_prob_label);
return convertLabelToString(getHighestProbLabel(object_classifications));
}

} // namespace autoware::object_recognition_utils
Expand Down
5 changes: 3 additions & 2 deletions common/autoware_object_recognition_utils/src/conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,12 @@ DetectedObject toDetectedObject(const TrackedObject & tracked_object)

DetectedObjects toDetectedObjects(const TrackedObjects & tracked_objects)
{
autoware_perception_msgs::msg::DetectedObjects detected_objects;
DetectedObjects detected_objects;
detected_objects.header = tracked_objects.header;

detected_objects.objects.reserve(tracked_objects.objects.size());
for (const auto & tracked_object : tracked_objects.objects) {
detected_objects.objects.push_back(toDetectedObject(tracked_object));
detected_objects.objects.emplace_back(toDetectedObject(tracked_object));
}
return detected_objects;
}
Expand Down
Loading