Skip to content

Commit 46531aa

Browse files
technolojinzulfaqar-azmi-t4xtk8532704pre-commit-ci[bot]kyoichi-sugahara
committed
fix: predicted path generation logic (autowarefoundation#1610)
* feat(lane_change): cancel hysteresis (autowarefoundation#6288) * feat(lane_change): cancel hysteresis Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Update documentation Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix the explanation of the hysteresis count Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Add parked parked RSS Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * support new perception_reproducer Signed-off-by: temkei.kem <1041084556@qq.com> * move files Signed-off-by: temkei.kem <1041084556@qq.com> * remove old files. Signed-off-by: temkei.kem <1041084556@qq.com> * fix pre-commit err Signed-off-by: temkei.kem <1041084556@qq.com> * style(pre-commit): autofix * feat(autoware_behavior_path_planner_common): disable feature of turning off blinker at low velocity (autowarefoundation#1571) Refactor turn signal decider logic and add support for detecting turn signals in turn lanes Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp> * fix a small bug about perception reproducer * style(pre-commit): autofix * feat(out_of_lane): ignore lanelets beyond the last path point (autowarefoundation#1554) * feat(out_of_lane): ignore lanelets beyond the last path point Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(behavior_velocity_run_out_module): exclude obstacle crossing ego… (autowarefoundation#1574) feat(behavior_velocity_run_out_module): exclude obstacle crossing ego back line (autowarefoundation#6680) * add method to ignore target obstacles that cross ego cut lane * WIP add debug support * add params and finish debug marker * change lane to line * use autoware utils to get the cut line * simplify code wit calcOffsetPose * Update readme and eliminate unused code * update readme * eliminate unused function * readme * comments and readme * eliminate unused include * typo * rename param for consistency * change lane to line for consistency * rename for clarity, add brief * fix indentation * update description * lane ->line * lane -> line --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * fix(lane_change): change stopping logic (RT0-33761) (autowarefoundation#1581) * RT0-33761 fix lane change stopping logic Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * copied from awf main tested implementation Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * doxygen comment Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Update planning/behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> * perf: PR 7237 autowarefoundation#7237 * perf RP8406 autowarefoundation#8406 * perf PR 8416 * perf PR 8427 * perf PR 8413 * tool PR 8456 * perf PR 8461 * perf PR 8388 * perf PR 8467 * perf PR 8471 * perf PR 8490 * perf PR 8751 * chore: fix format * perf PR 8657 * feat: improve lanelet search logic in getPredictedReferencePath() * sp develop remove non approved change (autowarefoundation#1611) Revert "feat: improve lanelet search logic in getPredictedReferencePath()" This reverts commit 5de95b0. * feat PR 8811 * fix PR 8973 * feat: improve lanelet search logic in getPredictedReferencePath() --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Signed-off-by: temkei.kem <1041084556@qq.com> Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp> Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Co-authored-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Co-authored-by: temkei.kem <1041084556@qq.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp> Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com> Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: danielsanchezaran <daniel.sanchez@tier4.jp> Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Co-authored-by: Shohei Sakai <saka1s.jp@gmail.com>
1 parent 09e4351 commit 46531aa

File tree

8 files changed

+810
-196
lines changed

8 files changed

+810
-196
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,142 @@
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+
#ifndef TIER4_AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_
15+
#define TIER4_AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_
16+
17+
#include <cstddef>
18+
#include <list>
19+
#include <optional>
20+
#include <unordered_map>
21+
#include <utility>
22+
23+
namespace tier4_autoware_utils
24+
{
25+
26+
/**
27+
* @brief A template class for LRU (Least Recently Used) Cache.
28+
*
29+
* This class implements a simple LRU cache using a combination of a list and a hash map.
30+
*
31+
* @tparam Key The type of keys.
32+
* @tparam Value The type of values.
33+
* @tparam Map The type of underlying map, defaulted to std::unordered_map.
34+
*/
35+
template <typename Key, typename Value, template <typename...> class Map = std::unordered_map>
36+
class LRUCache
37+
{
38+
private:
39+
size_t capacity_; ///< The maximum capacity of the cache.
40+
std::list<std::pair<Key, Value>> cache_list_; ///< List to maintain the order of elements.
41+
Map<Key, typename std::list<std::pair<Key, Value>>::iterator>
42+
cache_map_; ///< Map for fast access to elements.
43+
44+
public:
45+
/**
46+
* @brief Construct a new LRUCache object.
47+
*
48+
* @param size The capacity of the cache.
49+
*/
50+
explicit LRUCache(size_t size) : capacity_(size) {}
51+
52+
/**
53+
* @brief Get the capacity of the cache.
54+
*
55+
* @return The capacity of the cache.
56+
*/
57+
[[nodiscard]] size_t capacity() const { return capacity_; }
58+
59+
/**
60+
* @brief Insert a key-value pair into the cache.
61+
*
62+
* If the key already exists, its value is updated and it is moved to the front.
63+
* If the cache exceeds its capacity, the least recently used element is removed.
64+
*
65+
* @param key The key to insert.
66+
* @param value The value to insert.
67+
*/
68+
void put(const Key & key, const Value & value)
69+
{
70+
auto it = cache_map_.find(key);
71+
if (it != cache_map_.end()) {
72+
cache_list_.erase(it->second);
73+
}
74+
cache_list_.push_front({key, value});
75+
cache_map_[key] = cache_list_.begin();
76+
77+
if (cache_map_.size() > capacity_) {
78+
auto last = cache_list_.back();
79+
cache_map_.erase(last.first);
80+
cache_list_.pop_back();
81+
}
82+
}
83+
84+
/**
85+
* @brief Retrieve a value from the cache.
86+
*
87+
* If the key does not exist in the cache, std::nullopt is returned.
88+
* If the key exists, the value is returned and the element is moved to the front.
89+
*
90+
* @param key The key to retrieve.
91+
* @return The value associated with the key, or std::nullopt if the key does not exist.
92+
*/
93+
std::optional<Value> get(const Key & key)
94+
{
95+
auto it = cache_map_.find(key);
96+
if (it == cache_map_.end()) {
97+
return std::nullopt;
98+
}
99+
cache_list_.splice(cache_list_.begin(), cache_list_, it->second);
100+
return it->second->second;
101+
}
102+
103+
/**
104+
* @brief Clear the cache.
105+
*
106+
* This removes all elements from the cache.
107+
*/
108+
void clear()
109+
{
110+
cache_list_.clear();
111+
cache_map_.clear();
112+
}
113+
114+
/**
115+
* @brief Get the current size of the cache.
116+
*
117+
* @return The number of elements in the cache.
118+
*/
119+
[[nodiscard]] size_t size() const { return cache_map_.size(); }
120+
121+
/**
122+
* @brief Check if the cache is empty.
123+
*
124+
* @return True if the cache is empty, false otherwise.
125+
*/
126+
[[nodiscard]] bool empty() const { return cache_map_.empty(); }
127+
128+
/**
129+
* @brief Check if a key exists in the cache.
130+
*
131+
* @param key The key to check.
132+
* @return True if the key exists, false otherwise.
133+
*/
134+
[[nodiscard]] bool contains(const Key & key) const
135+
{
136+
return cache_map_.find(key) != cache_map_.end();
137+
}
138+
};
139+
140+
} // namespace tier4_autoware_utils
141+
142+
#endif // TIER4_AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
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+
#include "tier4_autoware_utils/system/lru_cache.hpp"
15+
16+
#include <gtest/gtest.h>
17+
18+
#include <chrono>
19+
#include <cstdint>
20+
#include <iostream>
21+
#include <utility>
22+
23+
using tier4_autoware_utils::LRUCache;
24+
25+
// Fibonacci calculation with LRU cache
26+
int64_t fibonacci_with_cache(int n, LRUCache<int, int64_t> * cache)
27+
{
28+
if (n <= 1) return n;
29+
30+
if (cache->contains(n)) {
31+
return *cache->get(n);
32+
}
33+
int64_t result = fibonacci_with_cache(n - 1, cache) + fibonacci_with_cache(n - 2, cache);
34+
cache->put(n, result);
35+
return result;
36+
}
37+
38+
// Fibonacci calculation without cache
39+
int64_t fibonacci_no_cache(int n)
40+
{
41+
if (n <= 1) return n;
42+
return fibonacci_no_cache(n - 1) + fibonacci_no_cache(n - 2);
43+
}
44+
45+
// Helper function to measure execution time
46+
template <typename Func, typename... Args>
47+
std::pair<int64_t, decltype(std::declval<Func>()(std::declval<Args>()...))> measure_time(
48+
Func func, Args &&... args)
49+
{
50+
auto start = std::chrono::high_resolution_clock::now();
51+
auto result = func(std::forward<Args>(args)...);
52+
auto end = std::chrono::high_resolution_clock::now();
53+
return {std::chrono::duration_cast<std::chrono::microseconds>(end - start).count(), result};
54+
}
55+
56+
// Test case to verify Fibonacci calculation results with and without cache
57+
TEST(FibonacciLRUCacheTest, CompareResultsAndPerformance)
58+
{
59+
const int max_n = 40; // Test range
60+
LRUCache<int, int64_t> cache(max_n); // Cache with capacity set to max_n
61+
62+
for (int i = 0; i <= max_n; ++i) {
63+
// Measure time for performance comparison
64+
auto [time_with_cache, result_with_cache] =
65+
measure_time([i, &cache]() { return fibonacci_with_cache(i, &cache); });
66+
auto [time_without_cache, result_without_cache] =
67+
measure_time([i]() { return fibonacci_no_cache(i); });
68+
69+
EXPECT_EQ(result_with_cache, result_without_cache) << "Mismatch at n = " << i;
70+
71+
// Print the calculation time
72+
std::cout << "n = " << i << ": With Cache = " << time_with_cache
73+
<< " μs, Without Cache = " << time_without_cache << " μs\n";
74+
75+
// // Clear the cache after each iteration to ensure fair comparison
76+
cache.clear();
77+
}
78+
}

perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+37-2
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include <rclcpp/rclcpp.hpp>
2121
#include <tier4_autoware_utils/ros/transform_listener.hpp>
22+
#include <tier4_autoware_utils/system/lru_cache.hpp>
2223
#include <tier4_autoware_utils/system/stop_watch.hpp>
2324

2425
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
@@ -31,7 +32,9 @@
3132
#include <visualization_msgs/msg/marker_array.hpp>
3233

3334
#include <lanelet2_core/Forward.h>
35+
#include <lanelet2_core/LaneletMap.h>
3436
#include <lanelet2_routing/Forward.h>
37+
#include <lanelet2_routing/LaneletPath.h>
3538
#include <lanelet2_traffic_rules/TrafficRules.h>
3639

3740
#include <deque>
@@ -41,6 +44,28 @@
4144
#include <utility>
4245
#include <vector>
4346

47+
namespace std
48+
{
49+
template <>
50+
struct hash<lanelet::routing::LaneletPaths>
51+
{
52+
// 0x9e3779b9 is a magic number. See
53+
// https://stackoverflow.com/questions/4948780/magic-number-in-boosthash-combine
54+
size_t operator()(const lanelet::routing::LaneletPaths & paths) const
55+
{
56+
size_t seed = 0;
57+
for (const auto & path : paths) {
58+
for (const auto & lanelet : path) {
59+
seed ^= hash<int64_t>{}(lanelet.id()) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U);
60+
}
61+
// Add a separator between paths
62+
seed ^= hash<int>{}(0) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U);
63+
}
64+
return seed;
65+
}
66+
};
67+
} // namespace std
68+
4469
namespace map_based_prediction
4570
{
4671
struct LateralKinematicsToLanelet
@@ -84,6 +109,7 @@ struct LaneletData
84109
struct PredictedRefPath
85110
{
86111
float probability;
112+
double width;
87113
PosePath path;
88114
Maneuver maneuver;
89115
};
@@ -132,6 +158,9 @@ class MapBasedPredictionNode : public rclcpp::Node
132158
// Crosswalk Entry Points
133159
lanelet::ConstLanelets crosswalks_;
134160

161+
// Fences
162+
lanelet::LaneletMapUPtr fence_layer_{nullptr};
163+
135164
// Parameters
136165
bool enable_delay_compensation_;
137166
double prediction_time_horizon_;
@@ -194,7 +223,8 @@ class MapBasedPredictionNode : public rclcpp::Node
194223
void updateObjectsHistory(
195224
const std_msgs::msg::Header & header, const TrackedObject & object,
196225
const LaneletsData & current_lanelets_data);
197-
226+
std::optional<size_t> searchProperStartingRefPathIndex(
227+
const TrackedObject & object, const PosePath & pose_path) const;
198228
std::vector<PredictedRefPath> getPredictedReferencePath(
199229
const TrackedObject & object, const LaneletsData & current_lanelets_data,
200230
const double object_detected_time);
@@ -217,7 +247,12 @@ class MapBasedPredictionNode : public rclcpp::Node
217247
const TrackedObject & object, const lanelet::routing::LaneletPaths & candidate_paths,
218248
const float path_probability, const ManeuverProbability & maneuver_probability,
219249
const Maneuver & maneuver, std::vector<PredictedRefPath> & reference_paths);
220-
std::vector<PosePath> convertPathType(const lanelet::routing::LaneletPaths & paths);
250+
251+
mutable tier4_autoware_utils::LRUCache<
252+
lanelet::routing::LaneletPaths, std::vector<std::pair<PosePath, double>>>
253+
lru_cache_of_convert_path_type_{1000};
254+
std::vector<std::pair<PosePath, double>> convertPathType(
255+
const lanelet::routing::LaneletPaths & paths) const;
221256

222257
void updateFuturePossibleLanelets(
223258
const TrackedObject & object, const lanelet::routing::LaneletPaths & paths);

perception/map_based_prediction/include/map_based_prediction/path_generator.hpp

+23-8
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,11 @@
2222
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
2323
#include <geometry_msgs/msg/pose.hpp>
2424
#include <geometry_msgs/msg/pose_stamped.hpp>
25+
#include <geometry_msgs/msg/quaternion.hpp>
2526
#include <geometry_msgs/msg/twist.hpp>
27+
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
28+
29+
#include <tf2/LinearMath/Quaternion.h>
2630

2731
#include <memory>
2832
#include <utility>
@@ -91,7 +95,7 @@ class PathGenerator
9195
PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object);
9296

9397
PredictedPath generatePathForOnLaneVehicle(
94-
const TrackedObject & object, const PosePath & ref_paths);
98+
const TrackedObject & object, const PosePath & ref_path, const double path_width = 0.0);
9599

96100
PredictedPath generatePathForCrosswalkUser(
97101
const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const;
@@ -109,23 +113,34 @@ class PathGenerator
109113
// Member functions
110114
PredictedPath generateStraightPath(const TrackedObject & object) const;
111115

112-
PredictedPath generatePolynomialPath(const TrackedObject & object, const PosePath & ref_path);
116+
PredictedPath generatePolynomialPath(
117+
const TrackedObject & object, const PosePath & ref_path, const double path_width,
118+
const double backlash_width) const;
113119

114120
FrenetPath generateFrenetPath(
115-
const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length);
121+
const FrenetPoint & current_point, const FrenetPoint & target_point,
122+
const double max_length) const;
116123
Eigen::Vector3d calcLatCoefficients(
117-
const FrenetPoint & current_point, const FrenetPoint & target_point, const double T);
124+
const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const;
118125
Eigen::Vector2d calcLonCoefficients(
119-
const FrenetPoint & current_point, const FrenetPoint & target_point, const double T);
126+
const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const;
127+
128+
std::vector<double> interpolationLerp(
129+
const std::vector<double> & base_keys, const std::vector<double> & base_values,
130+
const std::vector<double> & query_keys) const;
131+
std::vector<tf2::Quaternion> interpolationLerp(
132+
const std::vector<double> & base_keys, const std::vector<tf2::Quaternion> & base_values,
133+
const std::vector<double> & query_keys) const;
120134

121135
PosePath interpolateReferencePath(
122-
const PosePath & base_path, const FrenetPath & frenet_predicted_path);
136+
const PosePath & base_path, const FrenetPath & frenet_predicted_path) const;
123137

124138
PredictedPath convertToPredictedPath(
125139
const TrackedObject & object, const FrenetPath & frenet_predicted_path,
126-
const PosePath & ref_path);
140+
const PosePath & ref_path) const;
127141

128-
FrenetPoint getFrenetPoint(const TrackedObject & object, const PosePath & ref_path);
142+
FrenetPoint getFrenetPoint(
143+
const TrackedObject & object, const geometry_msgs::msg::Pose & ref_pose) const;
129144
};
130145
} // namespace map_based_prediction
131146

0 commit comments

Comments
 (0)