|
25 | 25 | #include <autoware/universe_utils/ros/published_time_publisher.hpp>
|
26 | 26 | #include <autoware/universe_utils/ros/transform_listener.hpp>
|
27 | 27 | #include <autoware/universe_utils/ros/uuid_helper.hpp>
|
| 28 | +#include <autoware/universe_utils/system/lru_cache.hpp> |
28 | 29 | #include <autoware/universe_utils/system/stop_watch.hpp>
|
29 | 30 | #include <autoware/universe_utils/system/time_keeper.hpp>
|
30 | 31 | #include <rclcpp/rclcpp.hpp>
|
|
41 | 42 | #include <lanelet2_core/Forward.h>
|
42 | 43 | #include <lanelet2_core/LaneletMap.h>
|
43 | 44 | #include <lanelet2_routing/Forward.h>
|
| 45 | +#include <lanelet2_routing/LaneletPath.h> |
44 | 46 | #include <lanelet2_traffic_rules/TrafficRules.h>
|
45 | 47 |
|
46 | 48 | #include <algorithm>
|
|
54 | 56 | #include <utility>
|
55 | 57 | #include <vector>
|
56 | 58 |
|
| 59 | +namespace std |
| 60 | +{ |
| 61 | +template <> |
| 62 | +struct hash<lanelet::routing::LaneletPaths> |
| 63 | +{ |
| 64 | + // 0x9e3779b9 is a magic number. See |
| 65 | + // https://stackoverflow.com/questions/4948780/magic-number-in-boosthash-combine |
| 66 | + size_t operator()(const lanelet::routing::LaneletPaths & paths) const |
| 67 | + { |
| 68 | + size_t seed = 0; |
| 69 | + for (const auto & path : paths) { |
| 70 | + for (const auto & lanelet : path) { |
| 71 | + seed ^= hash<int64_t>{}(lanelet.id()) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U); |
| 72 | + } |
| 73 | + // Add a separator between paths |
| 74 | + seed ^= hash<int>{}(0) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U); |
| 75 | + } |
| 76 | + return seed; |
| 77 | + } |
| 78 | +}; |
| 79 | +} // namespace std |
57 | 80 | namespace autoware::map_based_prediction
|
58 | 81 | {
|
59 | 82 | struct LateralKinematicsToLanelet
|
@@ -291,7 +314,10 @@ class MapBasedPredictionNode : public rclcpp::Node
|
291 | 314 | const float path_probability, const ManeuverProbability & maneuver_probability,
|
292 | 315 | const Maneuver & maneuver, std::vector<PredictedRefPath> & reference_paths,
|
293 | 316 | const double speed_limit = 0.0);
|
294 |
| - std::vector<PosePath> convertPathType(const lanelet::routing::LaneletPaths & paths); |
| 317 | + |
| 318 | + mutable universe_utils::LRUCache<lanelet::routing::LaneletPaths, std::vector<PosePath>> |
| 319 | + lru_cache_of_convert_path_type_{1000}; |
| 320 | + std::vector<PosePath> convertPathType(const lanelet::routing::LaneletPaths & paths) const; |
295 | 321 |
|
296 | 322 | void updateFuturePossibleLanelets(
|
297 | 323 | const TrackedObject & object, const lanelet::routing::LaneletPaths & paths);
|
|
0 commit comments