From 95bb2c61df36d4862432d437b7627a5d8fbc8a9c Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 15 Oct 2024 14:51:05 +0000 Subject: [PATCH] refactor(object_recognition_utils): add autoware prefix to object_recognition_utils (#8946) Signed-off-by: Esteve Fernandez --- .github/CODEOWNERS | 2 +- .../CMakeLists.txt | 6 ++--- .../README.md | 2 +- .../object_recognition_utils/conversion.hpp | 10 ++++---- .../object_recognition_utils/geometry.hpp | 10 ++++---- .../object_recognition_utils/matching.hpp | 12 ++++----- .../object_classification.hpp | 10 ++++---- .../object_recognition_utils.hpp | 25 +++++++++++++++++++ .../predicted_path_utils.hpp | 10 ++++---- .../object_recognition_utils/transform.hpp | 10 ++++---- .../package.xml | 4 +-- .../src/conversion.cpp | 6 ++--- .../src/predicted_path_utils.cpp | 6 ++--- .../test/src/test_conversion.cpp | 6 ++--- .../test/src/test_geometry.cpp | 4 +-- .../test/src/test_matching.cpp | 10 ++++---- .../test/src/test_object_classification.cpp | 20 +++++++-------- .../test/src/test_predicted_path_utils.cpp | 8 +++--- .../object_recognition_utils.hpp | 25 ------------------- .../perception_online_evaluator/package.xml | 2 +- .../src/metrics/detection_count.cpp | 5 ++-- .../src/metrics_calculator.cpp | 6 ++--- .../autoware_cluster_merger/package.xml | 2 +- .../src/cluster_merger_node.cpp | 6 ++--- .../package.xml | 2 +- .../src/lanelet_filter/lanelet_filter.cpp | 4 +-- .../obstacle_pointcloud_validator.cpp | 4 +-- .../occupancy_grid_map_validator.cpp | 10 ++++---- .../autoware_detection_by_tracker/package.xml | 2 +- .../src/detection_by_tracker_node.cpp | 20 +++++++-------- .../package.xml | 2 +- .../src/roi_detected_object_fusion/node.cpp | 11 ++++---- .../postprocess/non_maximum_suppression.cpp | 15 ++++++----- .../lib/ros_utils.cpp | 4 +-- .../autoware_lidar_centerpoint/package.xml | 2 +- .../postprocess/non_maximum_suppression.cpp | 15 ++++++----- .../lib/ros_utils.cpp | 4 +-- .../autoware_lidar_transfusion/package.xml | 2 +- .../tracker/model/tracker_base.hpp | 4 +-- .../uncertainty/uncertainty_processor.hpp | 2 +- .../lib/association/association.cpp | 6 ++--- .../lib/tracker/model/bicycle_tracker.cpp | 8 +++--- .../lib/tracker/model/big_vehicle_tracker.cpp | 8 +++--- .../model/multiple_vehicle_tracker.cpp | 4 ++- .../tracker/model/normal_vehicle_tracker.cpp | 8 +++--- .../tracker/model/pass_through_tracker.cpp | 4 +-- .../model/pedestrian_and_bicycle_tracker.cpp | 4 ++- .../lib/tracker/model/pedestrian_tracker.cpp | 8 +++--- .../lib/tracker/model/unknown_tracker.cpp | 4 +-- .../lib/uncertainty/uncertainty_processor.cpp | 2 +- .../autoware_multi_object_tracker/package.xml | 2 +- .../src/multi_object_tracker_node.cpp | 2 +- .../src/processor/processor.cpp | 8 +++--- perception/autoware_object_merger/package.xml | 2 +- .../src/association/data_association.cpp | 8 +++--- .../src/object_association_merger_node.cpp | 21 +++++++++------- .../package.xml | 2 +- .../src/radar_object_clustering_node.cpp | 4 +-- .../association/data_association.hpp | 2 +- .../tracker/model/tracker_base.hpp | 4 +-- .../autoware_radar_object_tracker/package.xml | 2 +- .../src/association/data_association.cpp | 4 +-- .../src/radar_object_tracker_node.cpp | 8 +++--- .../constant_turn_rate_motion_tracker.cpp | 6 +++-- .../tracker/model/linear_motion_tracker.cpp | 6 +++-- .../tensorrt_yolox/tensorrt_yolox_node.hpp | 2 +- .../autoware_tensorrt_yolox/package.xml | 2 +- .../src/tensorrt_yolox_node.cpp | 6 ++--- .../package.xml | 2 +- .../src/association/data_association.cpp | 9 ++++--- .../src/decorative_tracker_merger_node.cpp | 6 ++--- .../package.xml | 2 +- .../src/node.cpp | 6 ++--- .../src/utils.cpp | 5 ++-- .../package.xml | 2 +- .../src/scene.cpp | 6 ++--- .../src/utils/utils.cpp | 4 +-- .../package.xml | 2 +- .../package.xml | 2 +- .../path_safety_checker/objects_filtering.cpp | 4 +-- .../package.xml | 2 +- .../src/scene.cpp | 2 +- .../src/scene.hpp | 2 +- 83 files changed, 273 insertions(+), 240 deletions(-) rename common/{object_recognition_utils => autoware_object_recognition_utils}/CMakeLists.txt (79%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/README.md (87%) rename common/{object_recognition_utils/include => autoware_object_recognition_utils/include/autoware}/object_recognition_utils/conversion.hpp (80%) rename common/{object_recognition_utils/include => autoware_object_recognition_utils/include/autoware}/object_recognition_utils/geometry.hpp (85%) rename common/{object_recognition_utils/include => autoware_object_recognition_utils/include/autoware}/object_recognition_utils/matching.hpp (93%) rename common/{object_recognition_utils/include => autoware_object_recognition_utils/include/autoware}/object_recognition_utils/object_classification.hpp (94%) create mode 100644 common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_recognition_utils.hpp rename common/{object_recognition_utils/include => autoware_object_recognition_utils/include/autoware}/object_recognition_utils/predicted_path_utils.hpp (88%) rename common/{object_recognition_utils/include => autoware_object_recognition_utils/include/autoware}/object_recognition_utils/transform.hpp (95%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/package.xml (90%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/src/conversion.cpp (94%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/src/predicted_path_utils.cpp (96%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/test/src/test_conversion.cpp (98%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/test/src/test_geometry.cpp (97%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/test/src/test_matching.cpp (97%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/test/src/test_object_classification.cpp (95%) rename common/{object_recognition_utils => autoware_object_recognition_utils}/test/src/test_predicted_path_utils.cpp (97%) delete mode 100644 common/object_recognition_utils/include/object_recognition_utils/object_recognition_utils.hpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 7594271eae3c5..b00fe3371d11f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -6,6 +6,7 @@ common/autoware_grid_map_utils/** maxime.clement@tier4.jp common/autoware_interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp common/autoware_kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp common/autoware_motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +common/autoware_object_recognition_utils/** shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai common/autoware_path_distance_calculator/** isamu.takagi@tier4.jp @@ -24,7 +25,6 @@ common/fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabay common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/glog_component/** takamasa.horibe@tier4.jp common/goal_distance_calculator/** taiki.tanaka@tier4.jp -common/object_recognition_utils/** shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/polar_grid/** yukihiro.saito@tier4.jp common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp diff --git a/common/object_recognition_utils/CMakeLists.txt b/common/autoware_object_recognition_utils/CMakeLists.txt similarity index 79% rename from common/object_recognition_utils/CMakeLists.txt rename to common/autoware_object_recognition_utils/CMakeLists.txt index 4f05298573c18..9e1276db8d635 100644 --- a/common/object_recognition_utils/CMakeLists.txt +++ b/common/autoware_object_recognition_utils/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.14) -project(object_recognition_utils) +project(autoware_object_recognition_utils) find_package(autoware_cmake REQUIRED) autoware_package() find_package(Boost REQUIRED) -ament_auto_add_library(object_recognition_utils SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/predicted_path_utils.cpp src/conversion.cpp ) @@ -19,7 +19,7 @@ if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_object_recognition_utils ${test_files}) target_link_libraries(test_object_recognition_utils - object_recognition_utils + ${PROJECT_NAME} ) endif() diff --git a/common/object_recognition_utils/README.md b/common/autoware_object_recognition_utils/README.md similarity index 87% rename from common/object_recognition_utils/README.md rename to common/autoware_object_recognition_utils/README.md index 74a585e2dbd44..8d4eabd19c76d 100644 --- a/common/object_recognition_utils/README.md +++ b/common/autoware_object_recognition_utils/README.md @@ -1,4 +1,4 @@ -# object_recognition_utils +# autoware_object_recognition_utils ## Purpose diff --git a/common/object_recognition_utils/include/object_recognition_utils/conversion.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/conversion.hpp similarity index 80% rename from common/object_recognition_utils/include/object_recognition_utils/conversion.hpp rename to common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/conversion.hpp index 207f76a1c31a8..5b3be48cc2598 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/conversion.hpp +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/conversion.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ -#define OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ +#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ +#define AUTOWARE__OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ #include #include -namespace object_recognition_utils +namespace autoware::object_recognition_utils { using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; @@ -28,6 +28,6 @@ using autoware_perception_msgs::msg::TrackedObjects; DetectedObject toDetectedObject(const TrackedObject & tracked_object); DetectedObjects toDetectedObjects(const TrackedObjects & tracked_objects); TrackedObject toTrackedObject(const DetectedObject & detected_object); -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils -#endif // OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__CONVERSION_HPP_ diff --git a/common/object_recognition_utils/include/object_recognition_utils/geometry.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/geometry.hpp similarity index 85% rename from common/object_recognition_utils/include/object_recognition_utils/geometry.hpp rename to common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/geometry.hpp index 28cc9a786ecac..a5acc210d92be 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/geometry.hpp +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/geometry.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_RECOGNITION_UTILS__GEOMETRY_HPP_ -#define OBJECT_RECOGNITION_UTILS__GEOMETRY_HPP_ +#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__GEOMETRY_HPP_ +#define AUTOWARE__OBJECT_RECOGNITION_UTILS__GEOMETRY_HPP_ #include #include #include #include -namespace object_recognition_utils +namespace autoware::object_recognition_utils { template geometry_msgs::msg::Pose getPose([[maybe_unused]] const T & p) @@ -52,6 +52,6 @@ inline geometry_msgs::msg::Pose getPose(const autoware_perception_msgs::msg::Pre { return obj.kinematics.initial_pose_with_covariance.pose; } -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils -#endif // OBJECT_RECOGNITION_UTILS__GEOMETRY_HPP_ +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__GEOMETRY_HPP_ diff --git a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/matching.hpp similarity index 93% rename from common/object_recognition_utils/include/object_recognition_utils/matching.hpp rename to common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/matching.hpp index ae50227df1166..59c01c6d873e7 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/matching.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_RECOGNITION_UTILS__MATCHING_HPP_ -#define OBJECT_RECOGNITION_UTILS__MATCHING_HPP_ +#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__MATCHING_HPP_ +#define AUTOWARE__OBJECT_RECOGNITION_UTILS__MATCHING_HPP_ +#include "autoware/object_recognition_utils/geometry.hpp" #include "autoware/universe_utils/geometry/boost_geometry.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "object_recognition_utils/geometry.hpp" #include @@ -26,7 +26,7 @@ #include #include -namespace object_recognition_utils +namespace autoware::object_recognition_utils { using autoware::universe_utils::Polygon2d; // minimum area to avoid division by zero @@ -126,6 +126,6 @@ double get2dRecall(const T1 source_object, const T2 target_object) return std::min(1.0, intersection_area / target_area); } -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils -#endif // OBJECT_RECOGNITION_UTILS__MATCHING_HPP_ +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__MATCHING_HPP_ diff --git a/common/object_recognition_utils/include/object_recognition_utils/object_classification.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_classification.hpp similarity index 94% rename from common/object_recognition_utils/include/object_recognition_utils/object_classification.hpp rename to common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_classification.hpp index 4ffafc22339d6..432abcbe10c55 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/object_classification.hpp +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_classification.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_RECOGNITION_UTILS__OBJECT_CLASSIFICATION_HPP_ -#define OBJECT_RECOGNITION_UTILS__OBJECT_CLASSIFICATION_HPP_ +#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 #include -namespace object_recognition_utils +namespace autoware::object_recognition_utils { using autoware_perception_msgs::msg::ObjectClassification; @@ -169,6 +169,6 @@ inline std::string convertLabelToString( return convertLabelToString(highest_prob_label); } -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils -#endif // OBJECT_RECOGNITION_UTILS__OBJECT_CLASSIFICATION_HPP_ +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__OBJECT_CLASSIFICATION_HPP_ diff --git a/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_recognition_utils.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_recognition_utils.hpp new file mode 100644 index 0000000000000..d73e2e4dc67db --- /dev/null +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/object_recognition_utils.hpp @@ -0,0 +1,25 @@ +// Copyright 2022 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 AUTOWARE__OBJECT_RECOGNITION_UTILS__OBJECT_RECOGNITION_UTILS_HPP_ +#define AUTOWARE__OBJECT_RECOGNITION_UTILS__OBJECT_RECOGNITION_UTILS_HPP_ + +#include "autoware/object_recognition_utils/conversion.hpp" +#include "autoware/object_recognition_utils/geometry.hpp" +#include "autoware/object_recognition_utils/matching.hpp" +#include "autoware/object_recognition_utils/object_classification.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" +#include "autoware/object_recognition_utils/transform.hpp" + +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__OBJECT_RECOGNITION_UTILS_HPP_ diff --git a/common/object_recognition_utils/include/object_recognition_utils/predicted_path_utils.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/predicted_path_utils.hpp similarity index 88% rename from common/object_recognition_utils/include/object_recognition_utils/predicted_path_utils.hpp rename to common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/predicted_path_utils.hpp index 72e70185d553b..836b5296497e8 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/predicted_path_utils.hpp +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/predicted_path_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_ -#define OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_ +#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_ +#define AUTOWARE__OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_ #include "autoware/universe_utils/geometry/geometry.hpp" @@ -24,7 +24,7 @@ #include -namespace object_recognition_utils +namespace autoware::object_recognition_utils { /** * @brief Calculate Interpolated Pose from predicted path by time @@ -61,6 +61,6 @@ autoware_perception_msgs::msg::PredictedPath resamplePredictedPath( const autoware_perception_msgs::msg::PredictedPath & path, const double sampling_time_interval, const double sampling_horizon, const bool use_spline_for_xy = true, const bool use_spline_for_z = false); -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils -#endif // OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_ +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_ diff --git a/common/object_recognition_utils/include/object_recognition_utils/transform.hpp b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/transform.hpp similarity index 95% rename from common/object_recognition_utils/include/object_recognition_utils/transform.hpp rename to common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/transform.hpp index b03270133a52c..ced5956e079e6 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/transform.hpp +++ b/common/autoware_object_recognition_utils/include/autoware/object_recognition_utils/transform.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ -#define OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ +#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ +#define AUTOWARE__OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ #include @@ -71,7 +71,7 @@ namespace detail } } // namespace detail -namespace object_recognition_utils +namespace autoware::object_recognition_utils { template bool transformObjects( @@ -147,6 +147,6 @@ bool transformObjectsWithFeature( } return true; } -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils -#endif // OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ +#endif // AUTOWARE__OBJECT_RECOGNITION_UTILS__TRANSFORM_HPP_ diff --git a/common/object_recognition_utils/package.xml b/common/autoware_object_recognition_utils/package.xml similarity index 90% rename from common/object_recognition_utils/package.xml rename to common/autoware_object_recognition_utils/package.xml index a3f4a99300716..8fcc19ec7a53c 100644 --- a/common/object_recognition_utils/package.xml +++ b/common/autoware_object_recognition_utils/package.xml @@ -1,9 +1,9 @@ - object_recognition_utils + autoware_object_recognition_utils 0.1.0 - The object_recognition_utils package + The autoware_object_recognition_utils package Takayuki Murooka Shunsuke Miura Yoshi Ri diff --git a/common/object_recognition_utils/src/conversion.cpp b/common/autoware_object_recognition_utils/src/conversion.cpp similarity index 94% rename from common/object_recognition_utils/src/conversion.cpp rename to common/autoware_object_recognition_utils/src/conversion.cpp index c9c057ad93644..6f8e6aa27cfb4 100644 --- a/common/object_recognition_utils/src/conversion.cpp +++ b/common/autoware_object_recognition_utils/src/conversion.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "object_recognition_utils/conversion.hpp" +#include "autoware/object_recognition_utils/conversion.hpp" -namespace object_recognition_utils +namespace autoware::object_recognition_utils { using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; @@ -68,4 +68,4 @@ TrackedObject toTrackedObject(const DetectedObject & detected_object) tracked_object.shape = detected_object.shape; return tracked_object; } -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils diff --git a/common/object_recognition_utils/src/predicted_path_utils.cpp b/common/autoware_object_recognition_utils/src/predicted_path_utils.cpp similarity index 96% rename from common/object_recognition_utils/src/predicted_path_utils.cpp rename to common/autoware_object_recognition_utils/src/predicted_path_utils.cpp index 96c62d9f50323..196f82b69161a 100644 --- a/common/object_recognition_utils/src/predicted_path_utils.cpp +++ b/common/autoware_object_recognition_utils/src/predicted_path_utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "object_recognition_utils/predicted_path_utils.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/interpolation/linear_interpolation.hpp" #include "autoware/interpolation/spherical_linear_interpolation.hpp" @@ -20,7 +20,7 @@ #include -namespace object_recognition_utils +namespace autoware::object_recognition_utils { boost::optional calcInterpolatedPose( const autoware_perception_msgs::msg::PredictedPath & path, const double relative_time) @@ -129,4 +129,4 @@ autoware_perception_msgs::msg::PredictedPath resamplePredictedPath( resampled_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval); return resampled_path; } -} // namespace object_recognition_utils +} // namespace autoware::object_recognition_utils diff --git a/common/object_recognition_utils/test/src/test_conversion.cpp b/common/autoware_object_recognition_utils/test/src/test_conversion.cpp similarity index 98% rename from common/object_recognition_utils/test/src/test_conversion.cpp rename to common/autoware_object_recognition_utils/test/src/test_conversion.cpp index a9b462f9ec4c4..6a05771149ad2 100644 --- a/common/object_recognition_utils/test/src/test_conversion.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_conversion.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/object_recognition_utils/conversion.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/conversion.hpp" #include @@ -42,8 +42,8 @@ autoware_perception_msgs::msg::ObjectClassification createObjectClassification( // NOTE: covariance is not checked TEST(conversion, test_toDetectedObject) { + using autoware::object_recognition_utils::toDetectedObject; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::toDetectedObject; autoware_perception_msgs::msg::TrackedObject tracked_obj; // existence probability @@ -160,8 +160,8 @@ TEST(conversion, test_toDetectedObject) // NOTE: covariance is not checked TEST(conversion, test_toTrackedObject) { + using autoware::object_recognition_utils::toTrackedObject; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::toTrackedObject; autoware_perception_msgs::msg::DetectedObject detected_obj; // existence probability diff --git a/common/object_recognition_utils/test/src/test_geometry.cpp b/common/autoware_object_recognition_utils/test/src/test_geometry.cpp similarity index 97% rename from common/object_recognition_utils/test/src/test_geometry.cpp rename to common/autoware_object_recognition_utils/test/src/test_geometry.cpp index ab3ba8fcec7d4..f5165482a23bf 100644 --- a/common/object_recognition_utils/test/src/test_geometry.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_geometry.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "object_recognition_utils/geometry.hpp" +#include "autoware/object_recognition_utils/geometry.hpp" #include @@ -20,7 +20,7 @@ TEST(geometry, getPose) { - using object_recognition_utils::getPose; + using autoware::object_recognition_utils::getPose; const double x_ans = 1.0; const double y_ans = 2.0; diff --git a/common/object_recognition_utils/test/src/test_matching.cpp b/common/autoware_object_recognition_utils/test/src/test_matching.cpp similarity index 97% rename from common/object_recognition_utils/test/src/test_matching.cpp rename to common/autoware_object_recognition_utils/test/src/test_matching.cpp index 6005ac8d1efbc..aefc6251c6276 100644 --- a/common/object_recognition_utils/test/src/test_matching.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_matching.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/object_recognition_utils/matching.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/matching.hpp" #include @@ -37,8 +37,8 @@ geometry_msgs::msg::Pose createPose(const double x, const double y, const double TEST(matching, test_get2dIoU) { + using autoware::object_recognition_utils::get2dIoU; using autoware_perception_msgs::msg::DetectedObject; - using object_recognition_utils::get2dIoU; const double quart_circle = 0.16237976320958225; @@ -93,7 +93,7 @@ TEST(matching, test_get2dIoU) TEST(object_recognition_utils, test_get2dGeneralizedIoU) { - using object_recognition_utils::get2dGeneralizedIoU; + using autoware::object_recognition_utils::get2dGeneralizedIoU; // TODO(Shin-kyoto): // get2dGeneralizedIoU uses outer points of each polygon. // But these points contain an sampling error of outer line, @@ -153,8 +153,8 @@ TEST(object_recognition_utils, test_get2dGeneralizedIoU) TEST(matching, test_get2dPrecision) { + using autoware::object_recognition_utils::get2dPrecision; using autoware_perception_msgs::msg::DetectedObject; - using object_recognition_utils::get2dPrecision; const double quart_circle = 0.16237976320958225; { // non overlapped @@ -220,8 +220,8 @@ TEST(matching, test_get2dPrecision) TEST(matching, test_get2dRecall) { + using autoware::object_recognition_utils::get2dRecall; using autoware_perception_msgs::msg::DetectedObject; - using object_recognition_utils::get2dRecall; const double quart_circle = 0.16237976320958225; { // non overlapped diff --git a/common/object_recognition_utils/test/src/test_object_classification.cpp b/common/autoware_object_recognition_utils/test/src/test_object_classification.cpp similarity index 95% rename from common/object_recognition_utils/test/src/test_object_classification.cpp rename to common/autoware_object_recognition_utils/test/src/test_object_classification.cpp index 697a7e8447732..1482158581a8e 100644 --- a/common/object_recognition_utils/test/src/test_object_classification.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_object_classification.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "object_recognition_utils/object_classification.hpp" +#include "autoware/object_recognition_utils/object_classification.hpp" #include @@ -34,8 +34,8 @@ autoware_perception_msgs::msg::ObjectClassification createObjectClassification( TEST(object_classification, test_getHighestProbLabel) { + using autoware::object_recognition_utils::getHighestProbLabel; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::getHighestProbLabel; { // empty std::vector classifications; @@ -67,8 +67,8 @@ TEST(object_classification, test_getHighestProbLabel) // Test isVehicle TEST(object_classification, test_isVehicle) { + using autoware::object_recognition_utils::isVehicle; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::isVehicle; { // True Case with uint8_t EXPECT_TRUE(isVehicle(ObjectClassification::BICYCLE)); @@ -106,8 +106,8 @@ TEST(object_classification, test_isVehicle) // TEST isCarLikeVehicle TEST(object_classification, test_isCarLikeVehicle) { + using autoware::object_recognition_utils::isCarLikeVehicle; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::isCarLikeVehicle; { // True Case with uint8_t EXPECT_TRUE(isCarLikeVehicle(ObjectClassification::BUS)); @@ -157,8 +157,8 @@ TEST(object_classification, test_isCarLikeVehicle) // TEST isLargeVehicle TEST(object_classification, test_isLargeVehicle) { + using autoware::object_recognition_utils::isLargeVehicle; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::isLargeVehicle; { // True Case with uint8_t EXPECT_TRUE(isLargeVehicle(ObjectClassification::BUS)); @@ -197,8 +197,8 @@ TEST(object_classification, test_isLargeVehicle) TEST(object_classification, test_getHighestProbClassification) { + using autoware::object_recognition_utils::getHighestProbClassification; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::getHighestProbClassification; { // empty std::vector classifications; @@ -232,10 +232,10 @@ TEST(object_classification, test_getHighestProbClassification) TEST(object_classification, test_fromString) { + using autoware::object_recognition_utils::toLabel; + using autoware::object_recognition_utils::toObjectClassification; + using autoware::object_recognition_utils::toObjectClassifications; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::toLabel; - using object_recognition_utils::toObjectClassification; - using object_recognition_utils::toObjectClassifications; // toLabel { @@ -266,8 +266,8 @@ TEST(object_classification, test_fromString) TEST(object_classification, test_convertLabelToString) { + using autoware::object_recognition_utils::convertLabelToString; using autoware_perception_msgs::msg::ObjectClassification; - using object_recognition_utils::convertLabelToString; // from label { diff --git a/common/object_recognition_utils/test/src/test_predicted_path_utils.cpp b/common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp similarity index 97% rename from common/object_recognition_utils/test/src/test_predicted_path_utils.cpp rename to common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp index 228a0d097fde6..a93d253bfd052 100644 --- a/common/object_recognition_utils/test/src/test_predicted_path_utils.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" #include @@ -64,10 +64,10 @@ PredictedPath createTestPredictedPath( TEST(predicted_path_utils, testCalcInterpolatedPose) { + using autoware::object_recognition_utils::calcInterpolatedPose; using autoware::universe_utils::createQuaternionFromRPY; using autoware::universe_utils::createQuaternionFromYaw; using autoware::universe_utils::deg2rad; - using object_recognition_utils::calcInterpolatedPose; const auto path = createTestPredictedPath(100, 0.1, 1.0); @@ -130,10 +130,10 @@ TEST(predicted_path_utils, testCalcInterpolatedPose) TEST(predicted_path_utils, resamplePredictedPath_by_vector) { + using autoware::object_recognition_utils::resamplePredictedPath; using autoware::universe_utils::createQuaternionFromRPY; using autoware::universe_utils::createQuaternionFromYaw; using autoware::universe_utils::deg2rad; - using object_recognition_utils::resamplePredictedPath; const auto path = createTestPredictedPath(10, 1.0, 1.0); @@ -207,10 +207,10 @@ TEST(predicted_path_utils, resamplePredictedPath_by_vector) TEST(predicted_path_utils, resamplePredictedPath_by_sampling_time) { + using autoware::object_recognition_utils::resamplePredictedPath; using autoware::universe_utils::createQuaternionFromRPY; using autoware::universe_utils::createQuaternionFromYaw; using autoware::universe_utils::deg2rad; - using object_recognition_utils::resamplePredictedPath; const auto path = createTestPredictedPath(10, 1.0, 1.0); diff --git a/common/object_recognition_utils/include/object_recognition_utils/object_recognition_utils.hpp b/common/object_recognition_utils/include/object_recognition_utils/object_recognition_utils.hpp deleted file mode 100644 index 4a4ef4f246453..0000000000000 --- a/common/object_recognition_utils/include/object_recognition_utils/object_recognition_utils.hpp +++ /dev/null @@ -1,25 +0,0 @@ -// Copyright 2022 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 OBJECT_RECOGNITION_UTILS__OBJECT_RECOGNITION_UTILS_HPP_ -#define OBJECT_RECOGNITION_UTILS__OBJECT_RECOGNITION_UTILS_HPP_ - -#include "object_recognition_utils/conversion.hpp" -#include "object_recognition_utils/geometry.hpp" -#include "object_recognition_utils/matching.hpp" -#include "object_recognition_utils/object_classification.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" -#include "object_recognition_utils/transform.hpp" - -#endif // OBJECT_RECOGNITION_UTILS__OBJECT_RECOGNITION_UTILS_HPP_ diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index 23b1210063705..0103200511e73 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -19,6 +19,7 @@ autoware_lanelet2_extension autoware_motion_utils + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils autoware_vehicle_info_utils @@ -27,7 +28,6 @@ geometry_msgs glog nav_msgs - object_recognition_utils pluginlib rclcpp rclcpp_components diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp index 5859bf055d4aa..ab69ea9cb8c7b 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp @@ -14,8 +14,8 @@ #include "perception_online_evaluator/metrics/detection_count.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include "perception_online_evaluator/utils/objects_filtering.hpp" #include @@ -72,7 +72,8 @@ void DetectionCounter::addObjects( for (const auto & object : objects.objects) { const auto uuid = toHexString(object.object_id); - const auto label = object_recognition_utils::getHighestProbLabel(object.classification); + const auto label = + autoware::object_recognition_utils::getHighestProbLabel(object.classification); if (!isCountObject(label, parameters_->object_parameters)) { continue; } diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 212af8711a62e..fea4316fa6820 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -15,16 +15,16 @@ #include "perception_online_evaluator/metrics_calculator.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" +#include "autoware/object_recognition_utils/object_classification.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/object_classification.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include namespace perception_diagnostics { +using autoware::object_recognition_utils::convertLabelToString; using autoware::universe_utils::inverseTransformPoint; -using object_recognition_utils::convertLabelToString; std::optional MetricsCalculator::calculate(const Metric & metric) const { diff --git a/perception/autoware_cluster_merger/package.xml b/perception/autoware_cluster_merger/package.xml index 879cf1da2a565..ff3eb60ec9c45 100644 --- a/perception/autoware_cluster_merger/package.xml +++ b/perception/autoware_cluster_merger/package.xml @@ -12,11 +12,11 @@ ament_cmake_auto + autoware_object_recognition_utils autoware_test_utils autoware_universe_utils geometry_msgs message_filters - object_recognition_utils rclcpp rclcpp_components tier4_perception_msgs diff --git a/perception/autoware_cluster_merger/src/cluster_merger_node.cpp b/perception/autoware_cluster_merger/src/cluster_merger_node.cpp index 554196787c028..42e0ef005057f 100644 --- a/perception/autoware_cluster_merger/src/cluster_merger_node.cpp +++ b/perception/autoware_cluster_merger/src/cluster_merger_node.cpp @@ -14,7 +14,7 @@ #include "cluster_merger_node.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -52,9 +52,9 @@ void ClusterMergerNode::objectsCallback( DetectedObjectsWithFeature transformed_objects0; DetectedObjectsWithFeature transformed_objects1; if ( - !object_recognition_utils::transformObjectsWithFeature( + !autoware::object_recognition_utils::transformObjectsWithFeature( *input_objects0_msg, output_frame_id_, tf_buffer_, transformed_objects0) || - !object_recognition_utils::transformObjectsWithFeature( + !autoware::object_recognition_utils::transformObjectsWithFeature( *input_objects1_msg, output_frame_id_, tf_buffer_, transformed_objects1)) { return; } diff --git a/perception/autoware_detected_object_validation/package.xml b/perception/autoware_detected_object_validation/package.xml index b46c182d2cb57..4f136ad6270c8 100644 --- a/perception/autoware_detected_object_validation/package.xml +++ b/perception/autoware_detected_object_validation/package.xml @@ -19,12 +19,12 @@ autoware_lanelet2_extension autoware_map_msgs + autoware_object_recognition_utils autoware_perception_msgs autoware_test_utils autoware_universe_utils message_filters nav_msgs - object_recognition_utils pcl_conversions rclcpp rclcpp_components diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp index 59de872ae9b90..e54ffd5452e7c 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp @@ -14,11 +14,11 @@ #include "lanelet_filter.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware_lanelet2_extension/utility/message_conversion.hpp" #include "autoware_lanelet2_extension/utility/query.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -97,7 +97,7 @@ void ObjectLaneletFilterNode::objectCallback( return; } autoware_perception_msgs::msg::DetectedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( *input_msg, lanelet_frame_id_, tf_buffer_, transformed_objects)) { RCLCPP_ERROR(get_logger(), "Failed transform to %s.", lanelet_frame_id_.c_str()); return; diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp index 7f55c86080fd2..e3889ae8f6513 100644 --- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp +++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp @@ -16,8 +16,8 @@ #include "obstacle_pointcloud_validator.hpp" +#include #include -#include #include @@ -325,7 +325,7 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // Transform to pointcloud frame autoware_perception_msgs::msg::DetectedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( *input_objects, input_obstacle_pointcloud->header.frame_id, tf_buffer_, transformed_objects)) { // objects_pub_->publish(*input_objects); diff --git a/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp b/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp index 51df1929a300c..a78e2bf90d8c2 100644 --- a/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp +++ b/perception/autoware_detected_object_validation/src/occupancy_grid_map/occupancy_grid_map_validator.cpp @@ -16,9 +16,9 @@ #include "occupancy_grid_map_validator.hpp" +#include "autoware/object_recognition_utils/object_classification.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "object_recognition_utils/object_classification.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include @@ -68,7 +68,7 @@ void OccupancyGridBasedValidator::onObjectsAndOccGrid( // Transform to occ grid frame autoware_perception_msgs::msg::DetectedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( *input_objects, input_occ_grid->header.frame_id, tf_buffer_, transformed_objects)) return; @@ -80,7 +80,7 @@ void OccupancyGridBasedValidator::onObjectsAndOccGrid( const auto & transformed_object = transformed_objects.objects.at(i); const auto & object = input_objects->objects.at(i); const auto & label = object.classification.front().label; - if (object_recognition_utils::isCarLikeVehicle(label)) { + if (autoware::object_recognition_utils::isCarLikeVehicle(label)) { auto mask = getMask(*input_occ_grid, transformed_object); const float mean = mask ? cv::mean(occ_grid, mask.value())[0] * 0.01 : 1.0; if (mean_threshold_ < mean) output.objects.push_back(object); @@ -159,7 +159,7 @@ void OccupancyGridBasedValidator::showDebugImage( // Get vehicle mask image and calculate mean within mask. for (const auto & object : objects.objects) { const auto & label = object.classification.front().label; - if (object_recognition_utils::isCarLikeVehicle(label)) { + if (autoware::object_recognition_utils::isCarLikeVehicle(label)) { auto mask = getMask(ros_occ_grid, object); const float mean = mask ? cv::mean(occ_grid, mask.value())[0] * 0.01 : 1.0; if (mean_threshold_ < mean) { diff --git a/perception/autoware_detection_by_tracker/package.xml b/perception/autoware_detection_by_tracker/package.xml index 6f23baeefbd3e..e84e13c484e16 100644 --- a/perception/autoware_detection_by_tracker/package.xml +++ b/perception/autoware_detection_by_tracker/package.xml @@ -14,10 +14,10 @@ eigen3_cmake_module autoware_euclidean_cluster + autoware_object_recognition_utils autoware_shape_estimation autoware_universe_utils eigen - object_recognition_utils rclcpp rclcpp_components tf2 diff --git a/perception/autoware_detection_by_tracker/src/detection_by_tracker_node.cpp b/perception/autoware_detection_by_tracker/src/detection_by_tracker_node.cpp index 4c65500d96aaa..571b6682eb5b0 100644 --- a/perception/autoware_detection_by_tracker/src/detection_by_tracker_node.cpp +++ b/perception/autoware_detection_by_tracker/src/detection_by_tracker_node.cpp @@ -16,9 +16,9 @@ #include "detection_by_tracker_node.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -161,14 +161,14 @@ void DetectionByTracker::onObjects( tracker_handler_.estimateTrackedObjects(input_msg->header.stamp, objects); if ( !available_trackers || - !object_recognition_utils::transformObjects( + !autoware::object_recognition_utils::transformObjects( objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) { objects_pub_->publish(detected_objects); published_time_publisher_->publish_if_subscribed(objects_pub_, detected_objects.header.stamp); return; } // to simplify post processes, convert tracked_objects to DetectedObjects message. - tracked_objects = object_recognition_utils::toDetectedObjects(transformed_objects); + tracked_objects = autoware::object_recognition_utils::toDetectedObjects(transformed_objects); } debugger_->publishInitialObjects(*input_msg); debugger_->publishTrackedObjects(tracked_objects); @@ -233,9 +233,9 @@ void DetectionByTracker::divideUnderSegmentedObjects( } // detect under segmented cluster const float recall = - object_recognition_utils::get2dRecall(initial_object.object, tracked_object); + autoware::object_recognition_utils::get2dRecall(initial_object.object, tracked_object); const float precision = - object_recognition_utils::get2dPrecision(initial_object.object, tracked_object); + autoware::object_recognition_utils::get2dPrecision(initial_object.object, tracked_object); const bool is_under_segmented = (recall_min_threshold < recall && precision < precision_max_threshold); if (!is_under_segmented) { @@ -310,7 +310,7 @@ float DetectionByTracker::optimizeUnderSegmentedObject( if (!is_shape_estimated) { continue; } - const float iou = object_recognition_utils::get2dIoU( + const float iou = autoware::object_recognition_utils::get2dIoU( highest_iou_object_in_current_iter.object, target_object); if (highest_iou_in_current_iter < iou) { highest_iou_in_current_iter = iou; @@ -332,7 +332,7 @@ float DetectionByTracker::optimizeUnderSegmentedObject( // build output highest_iou_object.object.classification = target_object.classification; highest_iou_object.object.existence_probability = - object_recognition_utils::get2dIoU(target_object, highest_iou_object.object); + autoware::object_recognition_utils::get2dIoU(target_object, highest_iou_object.object); output = highest_iou_object; return highest_iou; @@ -370,8 +370,8 @@ void DetectionByTracker::mergeOverSegmentedObjects( } // If there is an initial object in the tracker, it will be merged. - const float precision = - object_recognition_utils::get2dPrecision(initial_object.object, extended_tracked_object); + const float precision = autoware::object_recognition_utils::get2dPrecision( + initial_object.object, extended_tracked_object); if (precision < precision_threshold) { continue; } @@ -401,7 +401,7 @@ void DetectionByTracker::mergeOverSegmentedObjects( } feature_object.object.existence_probability = - object_recognition_utils::get2dIoU(tracked_object, feature_object.object); + autoware::object_recognition_utils::get2dIoU(tracked_object, feature_object.object); setClusterInObjectWithFeature(in_cluster_objects.header, pcl_merged_cluster, feature_object); out_objects.feature_objects.push_back(feature_object); } diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index f08ab04bc6616..b494f2d13887d 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -18,6 +18,7 @@ autoware_euclidean_cluster autoware_lidar_centerpoint + autoware_object_recognition_utils autoware_perception_msgs autoware_point_types autoware_universe_utils @@ -25,7 +26,6 @@ image_geometry image_transport message_filters - object_recognition_utils perception_utils rclcpp rclcpp_components diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 39835b465d8af..043e648403f3b 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -14,7 +14,7 @@ #include "autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -50,8 +50,9 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) ignored_object_flags.resize(output_msg.objects.size()); for (std::size_t obj_i = 0; obj_i < output_msg.objects.size(); ++obj_i) { const auto & object = output_msg.objects.at(obj_i); - const auto label = object_recognition_utils::getHighestProbLabel(object.classification); - const auto pos = object_recognition_utils::getPose(object).position; + const auto label = + autoware::object_recognition_utils::getHighestProbLabel(object.classification); + const auto pos = autoware::object_recognition_utils::getPose(object).position; const auto object_sqr_dist = pos.x * pos.x + pos.y * pos.y; const auto prob_threshold = fusion_params_.passthrough_lower_bound_probability_thresholds.at(label); @@ -222,9 +223,9 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage( for (const auto & image_roi : image_rois) { const auto & object_roi = object_pair.second; const auto object_roi_label = - object_recognition_utils::getHighestProbLabel(object_roi.object.classification); + autoware::object_recognition_utils::getHighestProbLabel(object_roi.object.classification); const auto image_roi_label = - object_recognition_utils::getHighestProbLabel(image_roi.object.classification); + autoware::object_recognition_utils::getHighestProbLabel(image_roi.object.classification); if (!fusion_params_.can_assign_matrix(object_roi_label, image_roi_label)) { continue; } diff --git a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp index f7dd85b019250..8f3f0fa9b20e2 100644 --- a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp @@ -14,9 +14,9 @@ #include "autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp" +#include +#include #include -#include -#include namespace autoware::lidar_centerpoint { @@ -41,8 +41,10 @@ bool NonMaximumSuppression::isTargetLabel(const uint8_t label) bool NonMaximumSuppression::isTargetPairObject( const DetectedObject & object1, const DetectedObject & object2) { - const auto label1 = object_recognition_utils::getHighestProbLabel(object1.classification); - const auto label2 = object_recognition_utils::getHighestProbLabel(object2.classification); + const auto label1 = + autoware::object_recognition_utils::getHighestProbLabel(object1.classification); + const auto label2 = + autoware::object_recognition_utils::getHighestProbLabel(object2.classification); if (isTargetLabel(label1) && isTargetLabel(label2)) { return true; @@ -50,7 +52,8 @@ bool NonMaximumSuppression::isTargetPairObject( const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d( - object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2)); + autoware::object_recognition_utils::getPose(object1), + autoware::object_recognition_utils::getPose(object2)); return sqr_dist_2d <= search_sqr_dist_2d; } @@ -69,7 +72,7 @@ Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( } if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { - const double iou = object_recognition_utils::get2dIoU(target_obj, source_obj); + const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj); triangular_matrix(target_i, source_i) = iou; // NOTE: If the target object has any objects with iou > iou_threshold, it // will be suppressed regardless of later results. diff --git a/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp b/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp index feeab969e88bd..c76fa6567ab51 100644 --- a/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp +++ b/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp @@ -14,9 +14,9 @@ #include "autoware/lidar_centerpoint/ros_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/constants.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" namespace autoware::lidar_centerpoint { @@ -41,7 +41,7 @@ void box3DToDetectedObject( rclcpp::get_logger("lidar_centerpoint"), "Unexpected label: UNKNOWN is set."); } - if (object_recognition_utils::isCarLikeVehicle(classification.label)) { + if (autoware::object_recognition_utils::isCarLikeVehicle(classification.label)) { obj.kinematics.orientation_availability = autoware_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN; } diff --git a/perception/autoware_lidar_centerpoint/package.xml b/perception/autoware_lidar_centerpoint/package.xml index 07f67f7e3c11e..29a7bc122707e 100644 --- a/perception/autoware_lidar_centerpoint/package.xml +++ b/perception/autoware_lidar_centerpoint/package.xml @@ -12,9 +12,9 @@ ament_cmake_python autoware_cmake + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils - object_recognition_utils pcl_ros rclcpp rclcpp_components diff --git a/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp index 6e563f706e3b2..1ce151d2960ef 100644 --- a/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp @@ -14,9 +14,9 @@ #include "autoware/lidar_transfusion/postprocess/non_maximum_suppression.hpp" +#include +#include #include -#include -#include namespace autoware::lidar_transfusion { @@ -41,8 +41,10 @@ bool NonMaximumSuppression::isTargetLabel(const uint8_t label) bool NonMaximumSuppression::isTargetPairObject( const DetectedObject & object1, const DetectedObject & object2) { - const auto label1 = object_recognition_utils::getHighestProbLabel(object1.classification); - const auto label2 = object_recognition_utils::getHighestProbLabel(object2.classification); + const auto label1 = + autoware::object_recognition_utils::getHighestProbLabel(object1.classification); + const auto label2 = + autoware::object_recognition_utils::getHighestProbLabel(object2.classification); if (isTargetLabel(label1) && isTargetLabel(label2)) { return true; @@ -50,7 +52,8 @@ bool NonMaximumSuppression::isTargetPairObject( const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d( - object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2)); + autoware::object_recognition_utils::getPose(object1), + autoware::object_recognition_utils::getPose(object2)); return sqr_dist_2d <= search_sqr_dist_2d; } @@ -69,7 +72,7 @@ Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( } if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { - const double iou = object_recognition_utils::get2dIoU(target_obj, source_obj); + const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj); triangular_matrix(target_i, source_i) = iou; // NOTE: If the target object has any objects with iou > iou_threshold, it // will be suppressed regardless of later results. diff --git a/perception/autoware_lidar_transfusion/lib/ros_utils.cpp b/perception/autoware_lidar_transfusion/lib/ros_utils.cpp index ce2a8d1911941..88f6497f8d656 100644 --- a/perception/autoware_lidar_transfusion/lib/ros_utils.cpp +++ b/perception/autoware_lidar_transfusion/lib/ros_utils.cpp @@ -14,9 +14,9 @@ #include "autoware/lidar_transfusion/ros_utils.hpp" +#include #include #include -#include namespace autoware::lidar_transfusion { @@ -40,7 +40,7 @@ void box3DToDetectedObject( rclcpp::get_logger("lidar_transfusion"), "Unexpected label: UNKNOWN is set."); } - if (object_recognition_utils::isCarLikeVehicle(classification.label)) { + if (autoware::object_recognition_utils::isCarLikeVehicle(classification.label)) { obj.kinematics.orientation_availability = autoware_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN; } diff --git a/perception/autoware_lidar_transfusion/package.xml b/perception/autoware_lidar_transfusion/package.xml index 834afba1221ad..791832ef44bda 100644 --- a/perception/autoware_lidar_transfusion/package.xml +++ b/perception/autoware_lidar_transfusion/package.xml @@ -12,11 +12,11 @@ ament_cmake_auto autoware_cmake + autoware_object_recognition_utils autoware_perception_msgs autoware_point_types autoware_universe_utils launch_ros - object_recognition_utils pcl_ros rclcpp rclcpp_components diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp index bc52e49f763fd..0b9ea9c44a6cf 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp @@ -21,7 +21,7 @@ #define EIGEN_MPL2_ONLY #include "autoware/multi_object_tracker/utils/utils.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -79,7 +79,7 @@ class Tracker } std::uint8_t getHighestProbLabel() const { - return object_recognition_utils::getHighestProbLabel(classification_); + return autoware::object_recognition_utils::getHighestProbLabel(classification_); } // existence states diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp index 52781be1b8201..c67e71b38a6f9 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp @@ -20,7 +20,7 @@ #include "autoware/multi_object_tracker/object_model/object_model.hpp" -#include +#include #include diff --git a/perception/autoware_multi_object_tracker/lib/association/association.cpp b/perception/autoware_multi_object_tracker/lib/association/association.cpp index ac31cad4cc13c..0c809ee5f086d 100644 --- a/perception/autoware_multi_object_tracker/lib/association/association.cpp +++ b/perception/autoware_multi_object_tracker/lib/association/association.cpp @@ -16,7 +16,7 @@ #include "autoware/multi_object_tracker/association/solver/gnn_solver.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -165,7 +165,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const autoware_perception_msgs::msg::DetectedObject & measurement_object = measurements.objects.at(measurement_idx); const std::uint8_t measurement_label = - object_recognition_utils::getHighestProbLabel(measurement_object.classification); + autoware::object_recognition_utils::getHighestProbLabel(measurement_object.classification); double score = 0.0; if (can_assign_matrix_(tracker_label, measurement_label)) { @@ -210,7 +210,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( if (passed_gate) { const double min_iou = min_iou_matrix_(tracker_label, measurement_label); const double min_union_iou_area = 1e-2; - const double iou = object_recognition_utils::get2dIoU( + const double iou = autoware::object_recognition_utils::get2dIoU( measurement_object, tracked_object, min_union_iou_area); if (iou < min_iou) passed_gate = false; } diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp index 38a49e48d8d10..098ad39dd3df9 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp @@ -20,11 +20,11 @@ #include "autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/math/normalization.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -246,7 +246,9 @@ bool BicycleTracker::measure( // update classification const auto & current_classification = getClassification(); - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { setClassification(current_classification); } @@ -272,7 +274,7 @@ bool BicycleTracker::measure( bool BicycleTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp index d5913eccdf0bf..349ffb1eec634 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp @@ -20,11 +20,11 @@ #include "autoware/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/math/normalization.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -301,7 +301,9 @@ bool BigVehicleTracker::measure( // update classification const auto & current_classification = getClassification(); - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { setClassification(current_classification); } @@ -327,7 +329,7 @@ bool BigVehicleTracker::measure( bool BigVehicleTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp index a6e5021e4fe7d..4751e3d1c894f 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp @@ -48,7 +48,9 @@ bool MultipleVehicleTracker::measure( { big_vehicle_tracker_.measure(object, time, self_transform); normal_vehicle_tracker_.measure(object, time, self_transform); - if (object_recognition_utils::getHighestProbLabel(object.classification) != Label::UNKNOWN) + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) != + Label::UNKNOWN) updateClassification(object.classification); return true; } diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp index a9260201722b3..b4be5e42b0397 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp @@ -20,11 +20,11 @@ #include "autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/math/normalization.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -303,7 +303,9 @@ bool NormalVehicleTracker::measure( // update classification const auto & current_classification = getClassification(); - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { setClassification(current_classification); } @@ -329,7 +331,7 @@ bool NormalVehicleTracker::measure( bool NormalVehicleTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp index c872944fab3d7..f66e616241ae0 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp @@ -19,8 +19,8 @@ #include "autoware/multi_object_tracker/tracker/model/pass_through_tracker.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -91,7 +91,7 @@ bool PassThroughTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { using autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); object.kinematics.pose_with_covariance.covariance[XYZRPY_COV_IDX::X_X] = 0.0; diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp index 8c665e6078a2b..1b8018351f5a5 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp @@ -48,7 +48,9 @@ bool PedestrianAndBicycleTracker::measure( { pedestrian_tracker_.measure(object, time, self_transform); bicycle_tracker_.measure(object, time, self_transform); - if (object_recognition_utils::getHighestProbLabel(object.classification) != Label::UNKNOWN) + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) != + Label::UNKNOWN) updateClassification(object.classification); return true; } diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp index 591453a14f116..2135514df8485 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp @@ -20,11 +20,11 @@ #include "autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/math/normalization.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -242,7 +242,9 @@ bool PedestrianTracker::measure( object_ = object; const auto & current_classification = getClassification(); - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { setClassification(current_classification); } @@ -269,7 +271,7 @@ bool PedestrianTracker::measure( bool PedestrianTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp index 0648007e0b807..2805e43b88323 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp @@ -34,7 +34,7 @@ #else #include #endif -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" namespace autoware::multi_object_tracker { @@ -217,7 +217,7 @@ bool UnknownTracker::measure( bool UnknownTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp index 6770b298bdbda..840879f9bd7aa 100644 --- a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp +++ b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp @@ -108,7 +108,7 @@ DetectedObjects modelUncertainty(const DetectedObjects & detected_objects) continue; } const ObjectClassification & object_class = - object_recognition_utils::getHighestProbClassification(object.classification); + autoware::object_recognition_utils::getHighestProbClassification(object.classification); updating_objects.objects.push_back(modelUncertaintyByClass(object, object_class)); } return updating_objects; diff --git a/perception/autoware_multi_object_tracker/package.xml b/perception/autoware_multi_object_tracker/package.xml index 405ce7eced625..d7250293df28e 100644 --- a/perception/autoware_multi_object_tracker/package.xml +++ b/perception/autoware_multi_object_tracker/package.xml @@ -14,13 +14,13 @@ eigen3_cmake_module autoware_kalman_filter + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils diagnostic_updater eigen glog mussp - object_recognition_utils rclcpp rclcpp_components tf2 diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp index e5ffddb31ccce..24bf4ef9c123d 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp @@ -282,7 +282,7 @@ void MultiObjectTracker::runProcess( // Transform the objects to the world frame DetectedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( input_objects_with_uncertainty, world_frame_id_, tf_buffer_, transformed_objects)) { return; } diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.cpp b/perception/autoware_multi_object_tracker/src/processor/processor.cpp index 17871c89b5258..ba9b3d17fd20f 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.cpp @@ -15,7 +15,7 @@ #include "processor.hpp" #include "autoware/multi_object_tracker/tracker/tracker.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware_perception_msgs/msg/tracked_objects.hpp" @@ -90,7 +90,8 @@ std::shared_ptr TrackerProcessor::createNewTracker( const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const { - const std::uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification); + const std::uint8_t label = + autoware::object_recognition_utils::getHighestProbLabel(object.classification); if (tracker_map_.count(label) != 0) { const auto tracker = tracker_map_.at(label); if (tracker == "bicycle_tracker") @@ -168,7 +169,8 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) // Check the Intersection over Union (IoU) between the two objects const double min_union_iou_area = 1e-2; - const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); + const auto iou = + autoware::object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); const auto & label1 = (*itr1)->getHighestProbLabel(); const auto & label2 = (*itr2)->getHighestProbLabel(); bool should_delete_tracker1 = false; diff --git a/perception/autoware_object_merger/package.xml b/perception/autoware_object_merger/package.xml index e87ef8d81b01b..77c30aa6d4556 100644 --- a/perception/autoware_object_merger/package.xml +++ b/perception/autoware_object_merger/package.xml @@ -13,11 +13,11 @@ autoware_cmake eigen3_cmake_module + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils eigen mussp - object_recognition_utils rclcpp rclcpp_components tf2 diff --git a/perception/autoware_object_merger/src/association/data_association.cpp b/perception/autoware_object_merger/src/association/data_association.cpp index 8b40178b592f8..bec2d48469562 100644 --- a/perception/autoware_object_merger/src/association/data_association.cpp +++ b/perception/autoware_object_merger/src/association/data_association.cpp @@ -15,8 +15,8 @@ #include "autoware/object_merger/association/data_association.hpp" #include "autoware/object_merger/association/solver/gnn_solver.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -124,13 +124,13 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const autoware_perception_msgs::msg::DetectedObject & object1 = objects1.objects.at(objects1_idx); const std::uint8_t object1_label = - object_recognition_utils::getHighestProbLabel(object1.classification); + autoware::object_recognition_utils::getHighestProbLabel(object1.classification); for (size_t objects0_idx = 0; objects0_idx < objects0.objects.size(); ++objects0_idx) { const autoware_perception_msgs::msg::DetectedObject & object0 = objects0.objects.at(objects0_idx); const std::uint8_t object0_label = - object_recognition_utils::getHighestProbLabel(object0.classification); + autoware::object_recognition_utils::getHighestProbLabel(object0.classification); double score = 0.0; if (can_assign_matrix_(object1_label, object0_label)) { @@ -158,7 +158,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const double min_iou = min_iou_matrix_(object1_label, object0_label); const double min_union_iou_area = 1e-2; const double iou = - object_recognition_utils::get2dIoU(object0, object1, min_union_iou_area); + autoware::object_recognition_utils::get2dIoU(object0, object1, min_union_iou_area); if (iou < min_iou) passed_gate = false; } diff --git a/perception/autoware_object_merger/src/object_association_merger_node.cpp b/perception/autoware_object_merger/src/object_association_merger_node.cpp index 663a338649d3c..af9d0e15f4894 100644 --- a/perception/autoware_object_merger/src/object_association_merger_node.cpp +++ b/perception/autoware_object_merger/src/object_association_merger_node.cpp @@ -16,8 +16,8 @@ #include "autoware/object_merger/object_association_merger_node.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -40,18 +40,19 @@ bool isUnknownObjectOverlapped( const std::map & generalized_iou_threshold_map) { const double generalized_iou_threshold = generalized_iou_threshold_map.at( - object_recognition_utils::getHighestProbLabel(known_object.classification)); + autoware::object_recognition_utils::getHighestProbLabel(known_object.classification)); const double distance_threshold = distance_threshold_map.at( - object_recognition_utils::getHighestProbLabel(known_object.classification)); + autoware::object_recognition_utils::getHighestProbLabel(known_object.classification)); const double sq_distance_threshold = std::pow(distance_threshold, 2.0); const double sq_distance = autoware::universe_utils::calcSquaredDistance2d( unknown_object.kinematics.pose_with_covariance.pose, known_object.kinematics.pose_with_covariance.pose); if (sq_distance_threshold < sq_distance) return false; - const auto precision = object_recognition_utils::get2dPrecision(unknown_object, known_object); - const auto recall = object_recognition_utils::get2dRecall(unknown_object, known_object); + const auto precision = + autoware::object_recognition_utils::get2dPrecision(unknown_object, known_object); + const auto recall = autoware::object_recognition_utils::get2dRecall(unknown_object, known_object); const auto generalized_iou = - object_recognition_utils::get2dGeneralizedIoU(unknown_object, known_object); + autoware::object_recognition_utils::get2dGeneralizedIoU(unknown_object, known_object); return precision > precision_threshold || recall > recall_threshold || generalized_iou > generalized_iou_threshold; } @@ -142,9 +143,9 @@ void ObjectAssociationMergerNode::objectsCallback( /* transform to base_link coordinate */ autoware_perception_msgs::msg::DetectedObjects transformed_objects0, transformed_objects1; if ( - !object_recognition_utils::transformObjects( + !autoware::object_recognition_utils::transformObjects( *input_objects0_msg, base_link_frame_id_, tf_buffer_, transformed_objects0) || - !object_recognition_utils::transformObjects( + !autoware::object_recognition_utils::transformObjects( *input_objects1_msg, base_link_frame_id_, tf_buffer_, transformed_objects1)) { return; } @@ -198,7 +199,9 @@ void ObjectAssociationMergerNode::objectsCallback( unknown_objects.reserve(output_msg.objects.size()); known_objects.reserve(output_msg.objects.size()); for (const auto & object : output_msg.objects) { - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { unknown_objects.push_back(object); } else { known_objects.push_back(object); diff --git a/perception/autoware_radar_object_clustering/package.xml b/perception/autoware_radar_object_clustering/package.xml index d9c3464e02b18..00106ee38e82f 100644 --- a/perception/autoware_radar_object_clustering/package.xml +++ b/perception/autoware_radar_object_clustering/package.xml @@ -14,10 +14,10 @@ ament_cmake_auto + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils geometry_msgs - object_recognition_utils rclcpp rclcpp_components tf2 diff --git a/perception/autoware_radar_object_clustering/src/radar_object_clustering_node.cpp b/perception/autoware_radar_object_clustering/src/radar_object_clustering_node.cpp index 4db4c578f9f89..cf686e3ae1055 100644 --- a/perception/autoware_radar_object_clustering/src/radar_object_clustering_node.cpp +++ b/perception/autoware_radar_object_clustering/src/radar_object_clustering_node.cpp @@ -14,9 +14,9 @@ #include "radar_object_clustering_node.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include @@ -162,7 +162,7 @@ void RadarObjectClusteringNode::onObjects(const DetectedObjects::ConstSharedPtr // Fixed label correction if (node_param_.is_fixed_label) { clustered_output_object.classification.at(0).label = - object_recognition_utils::toLabel(node_param_.fixed_label); + autoware::object_recognition_utils::toLabel(node_param_.fixed_label); } // Fixed size correction diff --git a/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/association/data_association.hpp b/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/association/data_association.hpp index efde1e6763cdd..ad53f8f9d7bf0 100644 --- a/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/association/data_association.hpp +++ b/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/association/data_association.hpp @@ -21,9 +21,9 @@ #define EIGEN_MPL2_ONLY +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware_radar_object_tracker/association/solver/gnn_solver.hpp" #include "autoware_radar_object_tracker/tracker/tracker.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include diff --git a/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/tracker/model/tracker_base.hpp b/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/tracker/model/tracker_base.hpp index caea725ef8f81..cc51af599cdd9 100644 --- a/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/tracker/model/tracker_base.hpp +++ b/perception/autoware_radar_object_tracker/include/autoware_radar_object_tracker/tracker/model/tracker_base.hpp @@ -20,8 +20,8 @@ #define AUTOWARE_RADAR_OBJECT_TRACKER__TRACKER__MODEL__TRACKER_BASE_HPP_ #define EIGEN_MPL2_ONLY +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware_radar_object_tracker/utils/utils.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -68,7 +68,7 @@ class Tracker } std::uint8_t getHighestProbLabel() const { - return object_recognition_utils::getHighestProbLabel(classification_); + return autoware::object_recognition_utils::getHighestProbLabel(classification_); } int getNoMeasurementCount() const { return no_measurement_count_; } int getTotalNoMeasurementCount() const { return total_no_measurement_count_; } diff --git a/perception/autoware_radar_object_tracker/package.xml b/perception/autoware_radar_object_tracker/package.xml index 6829c26f797c7..3a18b93451d39 100644 --- a/perception/autoware_radar_object_tracker/package.xml +++ b/perception/autoware_radar_object_tracker/package.xml @@ -15,13 +15,13 @@ autoware_kalman_filter autoware_lanelet2_extension + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils eigen glog mussp nlohmann-json-dev - object_recognition_utils rclcpp rclcpp_components tf2 diff --git a/perception/autoware_radar_object_tracker/src/association/data_association.cpp b/perception/autoware_radar_object_tracker/src/association/data_association.cpp index 2d906ce55bcec..673ae084fb242 100644 --- a/perception/autoware_radar_object_tracker/src/association/data_association.cpp +++ b/perception/autoware_radar_object_tracker/src/association/data_association.cpp @@ -176,7 +176,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const autoware_perception_msgs::msg::DetectedObject & measurement_object = measurements.objects.at(measurement_idx); const std::uint8_t measurement_label = - object_recognition_utils::getHighestProbLabel(measurement_object.classification); + autoware::object_recognition_utils::getHighestProbLabel(measurement_object.classification); // Create a JSON object to hold the log data for this pair nlohmann::json pair_log_data; @@ -259,7 +259,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( if (passed_gate) { const double min_iou = min_iou_matrix_(tracker_label, measurement_label); const double min_union_iou_area = 1e-2; - const double iou = object_recognition_utils::get2dIoU( + const double iou = autoware::object_recognition_utils::get2dIoU( measurement_object, tracked_object, min_union_iou_area); if (iou < min_iou) { passed_gate = false; diff --git a/perception/autoware_radar_object_tracker/src/radar_object_tracker_node.cpp b/perception/autoware_radar_object_tracker/src/radar_object_tracker_node.cpp index 10bf11e46abb9..1815b8ed64b04 100644 --- a/perception/autoware_radar_object_tracker/src/radar_object_tracker_node.cpp +++ b/perception/autoware_radar_object_tracker/src/radar_object_tracker_node.cpp @@ -150,7 +150,7 @@ void RadarObjectTrackerNode::onMeasurement( /* transform to world coordinate */ autoware_perception_msgs::msg::DetectedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( *input_objects_msg, world_frame_id_, tf_buffer_, transformed_objects)) { return; } @@ -215,7 +215,8 @@ std::shared_ptr RadarObjectTrackerNode::createNewTracker( const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & /*self_transform*/) const { - const std::uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification); + const std::uint8_t label = + autoware::object_recognition_utils::getHighestProbLabel(object.classification); if (tracker_map_.count(label) != 0) { const auto tracker = tracker_map_.at(label); @@ -347,7 +348,8 @@ void RadarObjectTrackerNode::sanitizeTracker( } const double min_union_iou_area = 1e-2; - const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); + const auto iou = + autoware::object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); const auto & label1 = (*itr1)->getHighestProbLabel(); const auto & label2 = (*itr2)->getHighestProbLabel(); bool should_delete_tracker1 = false; diff --git a/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp b/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp index f30e4f984f8a1..47b9430616fc9 100644 --- a/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp +++ b/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp @@ -497,7 +497,9 @@ bool ConstantTurnRateMotionTracker::measure( { const auto & current_classification = getClassification(); object_ = object; - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { setClassification(current_classification); } @@ -517,7 +519,7 @@ bool ConstantTurnRateMotionTracker::measure( bool ConstantTurnRateMotionTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp b/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp index dbadb3366ba0c..6facac3707c56 100644 --- a/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp +++ b/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp @@ -516,7 +516,9 @@ bool LinearMotionTracker::measure( { const auto & current_classification = getClassification(); object_ = object; - if (object_recognition_utils::getHighestProbLabel(object.classification) == Label::UNKNOWN) { + if ( + autoware::object_recognition_utils::getHighestProbLabel(object.classification) == + Label::UNKNOWN) { setClassification(current_classification); } @@ -536,7 +538,7 @@ bool LinearMotionTracker::measure( bool LinearMotionTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { - object = object_recognition_utils::toTrackedObject(object_); + object = autoware::object_recognition_utils::toTrackedObject(object_); object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox_node.hpp b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox_node.hpp index 2e317139f27c0..905957178ebd6 100644 --- a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox_node.hpp +++ b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox_node.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__TENSORRT_YOLOX__TENSORRT_YOLOX_NODE_HPP_ #define AUTOWARE__TENSORRT_YOLOX__TENSORRT_YOLOX_NODE_HPP_ -#include "object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include #include diff --git a/perception/autoware_tensorrt_yolox/package.xml b/perception/autoware_tensorrt_yolox/package.xml index cd9dc6bac015d..749624bcbe5a3 100644 --- a/perception/autoware_tensorrt_yolox/package.xml +++ b/perception/autoware_tensorrt_yolox/package.xml @@ -19,12 +19,12 @@ cudnn_cmake_module tensorrt_cmake_module + autoware_object_recognition_utils autoware_perception_msgs cuda_utils cv_bridge image_transport libopencv-dev - object_recognition_utils perception_utils rclcpp rclcpp_components diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp index 2455411618ceb..753e51d51265c 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -14,7 +14,7 @@ #include "autoware/tensorrt_yolox/tensorrt_yolox_node.hpp" -#include "object_recognition_utils/object_classification.hpp" +#include "autoware/object_recognition_utils/object_classification.hpp" #include "perception_utils/run_length_encoder.hpp" #include @@ -168,8 +168,8 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg) object.feature.roi.width = yolox_object.width; object.feature.roi.height = yolox_object.height; object.object.existence_probability = yolox_object.score; - object.object.classification = - object_recognition_utils::toObjectClassifications(label_map_[yolox_object.type], 1.0f); + object.object.classification = autoware::object_recognition_utils::toObjectClassifications( + label_map_[yolox_object.type], 1.0f); out_objects.feature_objects.push_back(object); const auto left = std::max(0, static_cast(object.feature.roi.x_offset)); const auto top = std::max(0, static_cast(object.feature.roi.y_offset)); diff --git a/perception/autoware_tracking_object_merger/package.xml b/perception/autoware_tracking_object_merger/package.xml index 321016ac0ff48..ce4cf5276ab80 100644 --- a/perception/autoware_tracking_object_merger/package.xml +++ b/perception/autoware_tracking_object_merger/package.xml @@ -13,12 +13,12 @@ autoware_cmake eigen3_cmake_module + autoware_object_recognition_utils autoware_perception_msgs autoware_universe_utils eigen glog mussp - object_recognition_utils rclcpp rclcpp_components tf2 diff --git a/perception/autoware_tracking_object_merger/src/association/data_association.cpp b/perception/autoware_tracking_object_merger/src/association/data_association.cpp index 119c95c86daf8..771fcb5f1a484 100644 --- a/perception/autoware_tracking_object_merger/src/association/data_association.cpp +++ b/perception/autoware_tracking_object_merger/src/association/data_association.cpp @@ -14,10 +14,10 @@ #include "autoware/tracking_object_merger/association/data_association.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/tracking_object_merger/association/solver/gnn_solver.hpp" #include "autoware/tracking_object_merger/utils/utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -178,9 +178,9 @@ double DataAssociation::calcScoreBetweenObjects( const autoware_perception_msgs::msg::TrackedObject & object1) const { const std::uint8_t object1_label = - object_recognition_utils::getHighestProbLabel(object1.classification); + autoware::object_recognition_utils::getHighestProbLabel(object1.classification); const std::uint8_t object0_label = - object_recognition_utils::getHighestProbLabel(object0.classification); + autoware::object_recognition_utils::getHighestProbLabel(object0.classification); double score = 0.0; if (can_assign_matrix_(object1_label, object0_label)) { @@ -206,7 +206,8 @@ double DataAssociation::calcScoreBetweenObjects( if (passed_gate) { const double min_iou = min_iou_matrix_(object1_label, object0_label); const double min_union_iou_area = 1e-2; - const double iou = object_recognition_utils::get2dIoU(object0, object1, min_union_iou_area); + const double iou = + autoware::object_recognition_utils::get2dIoU(object0, object1, min_union_iou_area); if (iou < min_iou) passed_gate = false; } // max velocity diff gate diff --git a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp index 295a350071ac8..55d31a1b890cd 100644 --- a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp +++ b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp @@ -16,9 +16,9 @@ #include "autoware/tracking_object_merger/decorative_tracker_merger_node.hpp" +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "autoware/tracking_object_merger/association/solver/ssp.hpp" #include "autoware/tracking_object_merger/utils/utils.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -200,7 +200,7 @@ void DecorativeTrackerMergerNode::mainObjectsCallback( /* transform to target merge coordinate */ TrackedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( *main_objects, merge_frame_id_, tf_buffer_, transformed_objects)) { return; } @@ -258,7 +258,7 @@ void DecorativeTrackerMergerNode::subObjectsCallback(const TrackedObjects::Const { /* transform to target merge coordinate */ TrackedObjects transformed_objects; - if (!object_recognition_utils::transformObjects( + if (!autoware::object_recognition_utils::transformObjects( *msg, merge_frame_id_, tf_buffer_, transformed_objects)) { return; } diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index ed3cd2169e343..d1c3b8b00e069 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -22,6 +22,7 @@ autoware_interpolation autoware_lanelet2_extension autoware_motion_utils + autoware_object_recognition_utils autoware_osqp_interface autoware_perception_msgs autoware_planning_msgs @@ -31,7 +32,6 @@ autoware_vehicle_info_utils geometry_msgs nav_msgs - object_recognition_utils rclcpp rclcpp_components std_msgs diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index f5cac52a68681..37b82ecb66e74 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -16,12 +16,12 @@ #include "autoware/motion_utils/resample/resample.hpp" #include "autoware/motion_utils/trajectory/conversion.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/obstacle_cruise_planner/polygon_utils.hpp" #include "autoware/obstacle_cruise_planner/utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/ros/marker_helper.hpp" #include "autoware/universe_utils/ros/update_param.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -99,7 +99,7 @@ std::vector resampleHighestConfidencePredictedPaths( continue; } resampled_paths.push_back( - object_recognition_utils::resamplePredictedPath(path, time_interval, time_horizon)); + autoware::object_recognition_utils::resamplePredictedPath(path, time_interval, time_horizon)); } return resampled_paths; @@ -1758,7 +1758,7 @@ std::optional ObstacleCruisePlannerNode::createStopObstacleForPred if (resampled_predicted_paths.empty() || resampled_predicted_paths.front().path.empty()) { return false; } - const auto future_obj_pose = object_recognition_utils::calcInterpolatedPose( + const auto future_obj_pose = autoware::object_recognition_utils::calcInterpolatedPose( resampled_predicted_paths.front(), time_to_reach_stop_point - p.collision_time_margin); Obstacle tmp_future_obs = obstacle; diff --git a/planning/autoware_obstacle_cruise_planner/src/utils.cpp b/planning/autoware_obstacle_cruise_planner/src/utils.cpp index 8162d8036d9dc..bc52e800c8fc5 100644 --- a/planning/autoware_obstacle_cruise_planner/src/utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/utils.cpp @@ -14,8 +14,8 @@ #include "autoware/obstacle_cruise_planner/utils.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/ros/marker_helper.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" namespace obstacle_cruise_utils { @@ -30,7 +30,8 @@ std::optional getCurrentObjectPoseFromPredictedPath( return std::nullopt; } - const auto pose = object_recognition_utils::calcInterpolatedPose(predicted_path, rel_time); + const auto pose = + autoware::object_recognition_utils::calcInterpolatedPose(predicted_path, rel_time); if (!pose) { return std::nullopt; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml index 9308aab7642f5..858bc78de09eb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml @@ -20,6 +20,7 @@ autoware_behavior_path_planner_common autoware_lanelet2_extension autoware_motion_utils + autoware_object_recognition_utils autoware_perception_msgs autoware_planning_msgs autoware_signal_processing @@ -27,7 +28,6 @@ autoware_vehicle_msgs geometry_msgs lanelet2_core - object_recognition_utils pluginlib rclcpp tf2 diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index 3fa3f04435e87..852a3fe0feedf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -16,9 +16,9 @@ #include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/signal_processing/lowpass_filter_1d.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -796,7 +796,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje return is_object_left; } const auto future_obj_pose = - object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); + autoware::object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); const size_t future_obj_idx = autoware::motion_utils::findNearestIndex(input_path.points, future_obj_pose->position); @@ -1001,7 +1001,7 @@ DynamicObstacleAvoidanceModule::calcCollisionSection( const auto future_ego_pose = ego_path.at(i); const auto future_obj_pose = - object_recognition_utils::calcInterpolatedPose(obj_path, elapsed_time); + autoware::object_recognition_utils::calcInterpolatedPose(obj_path, elapsed_time); if (future_obj_pose) { const double dist_ego_to_obj = diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index c4fe5fa9902c5..82a832d30c0b5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -24,8 +24,8 @@ #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/traffic_light_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -990,7 +990,7 @@ ExtendedPredictedObject transform( if (t < prepare_duration && obj_vel_norm < velocity_threshold) { continue; } - const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); + const auto obj_pose = autoware::object_recognition_utils::calcInterpolatedPose(path, t); if (obj_pose) { const auto obj_polygon = autoware::universe_utils::toPolygon2d(*obj_pose, object.shape); extended_object.predicted_paths.at(i).path.emplace_back( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index 6196a4f02cff9..1c3509bc22482 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -44,6 +44,7 @@ autoware_lane_departure_checker autoware_lanelet2_extension autoware_motion_utils + autoware_object_recognition_utils autoware_path_sampler autoware_perception_msgs autoware_planning_msgs @@ -57,7 +58,6 @@ libboost-dev libopencv-dev magic_enum - object_recognition_utils pluginlib rclcpp rclcpp_components diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index 28b79b502599d..d98e832e23e00 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -48,6 +48,7 @@ autoware_lane_departure_checker autoware_lanelet2_extension autoware_motion_utils + autoware_object_recognition_utils autoware_objects_of_interest_marker_interface autoware_perception_msgs autoware_planning_msgs @@ -57,7 +58,6 @@ autoware_vehicle_info_utils geometry_msgs magic_enum - object_recognition_utils rclcpp tf2 tier4_planning_msgs diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 20221fff82175..f183f5160cea8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -15,7 +15,7 @@ #include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" -#include "object_recognition_utils/predicted_path_utils.hpp" +#include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include #include @@ -336,7 +336,7 @@ ExtendedPredictedObject transform( // Create path based on time horizon and resolution for (double t = 0.0; t < safety_check_time_horizon + 1e-3; t += safety_check_time_resolution) { - const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); + const auto obj_pose = autoware::object_recognition_utils::calcInterpolatedPose(path, t); if (obj_pose) { const auto obj_polygon = autoware::universe_utils::toPolygon2d(*obj_pose, object.shape); extended_object.predicted_paths[i].path.emplace_back( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index ce6cf92fc6450..b8fc098826e7a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -22,6 +22,7 @@ autoware_behavior_velocity_crosswalk_module autoware_behavior_velocity_planner_common autoware_motion_utils + autoware_object_recognition_utils autoware_perception_msgs autoware_planning_msgs autoware_route_handler @@ -31,7 +32,6 @@ geometry_msgs libboost-dev message_filters - object_recognition_utils pcl_conversions pluginlib rclcpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 0a38e8d47ea36..5a219f654561a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -37,7 +37,7 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using object_recognition_utils::convertLabelToString; +using autoware::object_recognition_utils::convertLabelToString; RunOutModule::RunOutModule( const int64_t module_id, const std::shared_ptr & planner_data, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 7d8513485ac52..4f326aef298be 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -15,9 +15,9 @@ #ifndef SCENE_HPP_ #define SCENE_HPP_ +#include "autoware/object_recognition_utils/object_recognition_utils.hpp" #include "debug.hpp" #include "dynamic_obstacle.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include "state_machine.hpp" #include "utils.hpp"