|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ |
| 16 | +#define PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ |
| 17 | + |
| 18 | +#include "perception_online_evaluator/metrics/deviation_metrics.hpp" |
| 19 | +#include "perception_online_evaluator/metrics/metric.hpp" |
| 20 | +#include "perception_online_evaluator/parameters.hpp" |
| 21 | +#include "perception_online_evaluator/stat.hpp" |
| 22 | + |
| 23 | +#include <rclcpp/time.hpp> |
| 24 | + |
| 25 | +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" |
| 26 | +#include "geometry_msgs/msg/pose.hpp" |
| 27 | +#include <unique_identifier_msgs/msg/uuid.hpp> |
| 28 | + |
| 29 | +#include <algorithm> |
| 30 | +#include <map> |
| 31 | +#include <optional> |
| 32 | +#include <utility> |
| 33 | +#include <vector> |
| 34 | + |
| 35 | +namespace perception_diagnostics |
| 36 | +{ |
| 37 | +using autoware_auto_perception_msgs::msg::PredictedObject; |
| 38 | +using autoware_auto_perception_msgs::msg::PredictedObjects; |
| 39 | +using geometry_msgs::msg::Point; |
| 40 | +using geometry_msgs::msg::Pose; |
| 41 | +using unique_identifier_msgs::msg::UUID; |
| 42 | + |
| 43 | +struct ObjectData |
| 44 | +{ |
| 45 | + PredictedObject object; |
| 46 | + std::vector<std::pair<Pose, Pose>> path_pairs; |
| 47 | + |
| 48 | + std::vector<Pose> getPredictedPath() const |
| 49 | + { |
| 50 | + std::vector<Pose> path; |
| 51 | + path.resize(path_pairs.size()); |
| 52 | + std::transform( |
| 53 | + path_pairs.begin(), path_pairs.end(), path.begin(), |
| 54 | + [](const std::pair<Pose, Pose> & pair) -> Pose { return pair.first; }); |
| 55 | + return path; |
| 56 | + } |
| 57 | + |
| 58 | + std::vector<Pose> getHistoryPath() const |
| 59 | + { |
| 60 | + std::vector<Pose> path; |
| 61 | + path.resize(path_pairs.size()); |
| 62 | + std::transform( |
| 63 | + path_pairs.begin(), path_pairs.end(), path.begin(), |
| 64 | + [](const std::pair<Pose, Pose> & pair) -> Pose { return pair.second; }); |
| 65 | + return path; |
| 66 | + } |
| 67 | +}; |
| 68 | +using ObjectDataMap = std::unordered_map<std::string, ObjectData>; |
| 69 | + |
| 70 | +// pair of history_path and smoothed_history_path for each object id |
| 71 | +using HistoryPathMap = |
| 72 | + std::unordered_map<std::string, std::pair<std::vector<Pose>, std::vector<Pose>>>; |
| 73 | + |
| 74 | +class MetricsCalculator |
| 75 | +{ |
| 76 | +public: |
| 77 | + explicit MetricsCalculator(const std::shared_ptr<Parameters> & parameters) |
| 78 | + : parameters_(parameters){}; |
| 79 | + |
| 80 | + /** |
| 81 | + * @brief calculate |
| 82 | + * @param [in] metric Metric enum value |
| 83 | + * @return map of string describing the requested metric and the calculated value |
| 84 | + */ |
| 85 | + std::optional<MetricStatMap> calculate(const Metric & metric) const; |
| 86 | + |
| 87 | + /** |
| 88 | + * @brief set the dynamic objects used to calculate obstacle metrics |
| 89 | + * @param [in] objects predicted objects |
| 90 | + */ |
| 91 | + void setPredictedObjects(const PredictedObjects & objects); |
| 92 | + |
| 93 | + HistoryPathMap getHistoryPathMap() const { return history_path_map_; } |
| 94 | + ObjectDataMap getDebugObjectData() const { return debug_target_object_; } |
| 95 | + |
| 96 | +private: |
| 97 | + std::shared_ptr<Parameters> parameters_; |
| 98 | + |
| 99 | + // Store predicted objects information and calculation results |
| 100 | + std::unordered_map<std::string, std::map<rclcpp::Time, PredictedObject>> object_map_; |
| 101 | + HistoryPathMap history_path_map_; |
| 102 | + |
| 103 | + rclcpp::Time current_stamp_; |
| 104 | + |
| 105 | + // debug |
| 106 | + mutable ObjectDataMap debug_target_object_; |
| 107 | + |
| 108 | + // Functions to calculate history path |
| 109 | + void updateHistoryPath(); |
| 110 | + std::vector<Pose> averageFilterPath( |
| 111 | + const std::vector<Pose> & path, const size_t window_size) const; |
| 112 | + std::vector<Pose> generateHistoryPathWithPrev( |
| 113 | + const std::vector<Pose> & prev_history_path, const Pose & new_pose, const size_t window_size); |
| 114 | + |
| 115 | + // Update object data |
| 116 | + void updateObjects( |
| 117 | + const std::string uuid, const rclcpp::Time stamp, const PredictedObject & object); |
| 118 | + void deleteOldObjects(const rclcpp::Time stamp); |
| 119 | + |
| 120 | + // Calculate metrics |
| 121 | + MetricStatMap calcLateralDeviationMetrics(const PredictedObjects & objects) const; |
| 122 | + MetricStatMap calcYawDeviationMetrics(const PredictedObjects & objects) const; |
| 123 | + MetricStatMap calcPredictedPathDeviationMetrics(const PredictedObjects & objects) const; |
| 124 | + Stat<double> calcPredictedPathDeviationMetrics( |
| 125 | + const PredictedObjects & objects, const double time_horizon) const; |
| 126 | + |
| 127 | + bool hasPassedTime(const rclcpp::Time stamp) const; |
| 128 | + bool hasPassedTime(const std::string uuid, const rclcpp::Time stamp) const; |
| 129 | + double getTimeDelay() const; |
| 130 | + |
| 131 | + // Extract object |
| 132 | + rclcpp::Time getClosestStamp(const rclcpp::Time stamp) const; |
| 133 | + std::optional<PredictedObject> getObjectByStamp( |
| 134 | + const std::string uuid, const rclcpp::Time stamp) const; |
| 135 | + PredictedObjects getObjectsByStamp(const rclcpp::Time stamp) const; |
| 136 | + |
| 137 | +}; // class MetricsCalculator |
| 138 | + |
| 139 | +} // namespace perception_diagnostics |
| 140 | + |
| 141 | +#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ |
0 commit comments