Skip to content

Commit 93b9a5b

Browse files
authored
perf(autoware_map_based_prediction): speed up map based prediction by using lru cache in convertPathType (#8461)
feat(autoware_map_based_prediction): speed up map based prediction by using lru cache in convertPathType Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
1 parent 142795a commit 93b9a5b

File tree

2 files changed

+34
-2
lines changed

2 files changed

+34
-2
lines changed

perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+27-1
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
2626
#include <autoware/universe_utils/ros/transform_listener.hpp>
2727
#include <autoware/universe_utils/ros/uuid_helper.hpp>
28+
#include <autoware/universe_utils/system/lru_cache.hpp>
2829
#include <autoware/universe_utils/system/stop_watch.hpp>
2930
#include <autoware/universe_utils/system/time_keeper.hpp>
3031
#include <rclcpp/rclcpp.hpp>
@@ -41,6 +42,7 @@
4142
#include <lanelet2_core/Forward.h>
4243
#include <lanelet2_core/LaneletMap.h>
4344
#include <lanelet2_routing/Forward.h>
45+
#include <lanelet2_routing/LaneletPath.h>
4446
#include <lanelet2_traffic_rules/TrafficRules.h>
4547

4648
#include <algorithm>
@@ -54,6 +56,27 @@
5456
#include <utility>
5557
#include <vector>
5658

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
5780
namespace autoware::map_based_prediction
5881
{
5982
struct LateralKinematicsToLanelet
@@ -291,7 +314,10 @@ class MapBasedPredictionNode : public rclcpp::Node
291314
const float path_probability, const ManeuverProbability & maneuver_probability,
292315
const Maneuver & maneuver, std::vector<PredictedRefPath> & reference_paths,
293316
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;
295321

296322
void updateFuturePossibleLanelets(
297323
const TrackedObject & object, const lanelet::routing::LaneletPaths & paths);

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -922,6 +922,7 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg
922922
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
923923
lanelet::utils::conversion::fromBinMsg(
924924
*msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
925+
lru_cache_of_convert_path_type_.clear(); // clear cache
925926
RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Map is loaded");
926927

927928
const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
@@ -2373,10 +2374,14 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability(
23732374
}
23742375

23752376
std::vector<PosePath> MapBasedPredictionNode::convertPathType(
2376-
const lanelet::routing::LaneletPaths & paths)
2377+
const lanelet::routing::LaneletPaths & paths) const
23772378
{
23782379
autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_);
23792380

2381+
if (lru_cache_of_convert_path_type_.contains(paths)) {
2382+
return *lru_cache_of_convert_path_type_.get(paths);
2383+
}
2384+
23802385
std::vector<PosePath> converted_paths;
23812386
for (const auto & path : paths) {
23822387
PosePath converted_path;
@@ -2460,6 +2465,7 @@ std::vector<PosePath> MapBasedPredictionNode::convertPathType(
24602465
converted_paths.push_back(resampled_converted_path);
24612466
}
24622467

2468+
lru_cache_of_convert_path_type_.put(paths, converted_paths);
24632469
return converted_paths;
24642470
}
24652471

0 commit comments

Comments
 (0)