Skip to content

Commit bd59970

Browse files
technolojinsoblin
andauthored
refactor(autoware_map_based_prediction): refactoring lanelet path prediction and pose path conversion (#9104)
* refactor: update predictObjectManeuver function parameters Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: update hash function for LaneletPath in map_based_prediction_node.hpp Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: path list rename Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: take the path conversion out of the lanelet prediction Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: lanelet possible paths Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: separate converter of lanelet path to pose path Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: block each path lanelet process Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: fix time keeper Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * Update perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> Co-authored-by: Mamoru Sobue <hilo.soblin@gmail.com>
1 parent 631279c commit bd59970

File tree

2 files changed

+283
-248
lines changed

2 files changed

+283
-248
lines changed

Diff for: perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+21-29
Original file line numberDiff line numberDiff line change
@@ -59,19 +59,15 @@
5959
namespace std
6060
{
6161
template <>
62-
struct hash<lanelet::routing::LaneletPaths>
62+
struct hash<lanelet::routing::LaneletPath>
6363
{
6464
// 0x9e3779b9 is a magic number. See
6565
// https://stackoverflow.com/questions/4948780/magic-number-in-boosthash-combine
66-
size_t operator()(const lanelet::routing::LaneletPaths & paths) const
66+
size_t operator()(const lanelet::routing::LaneletPath & path) const
6767
{
6868
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);
69+
for (const auto & lanelet : path) {
70+
seed ^= hash<int64_t>{}(lanelet.id()) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U);
7571
}
7672
return seed;
7773
}
@@ -158,6 +154,7 @@ using autoware_perception_msgs::msg::TrafficLightGroupArray;
158154
using autoware_planning_msgs::msg::TrajectoryPoint;
159155
using tier4_debug_msgs::msg::StringStamped;
160156
using TrajectoryPoints = std::vector<TrajectoryPoint>;
157+
using LaneletPathWithPathInfo = std::pair<lanelet::routing::LaneletPath, PredictedRefPath>;
161158
class MapBasedPredictionNode : public rclcpp::Node
162159
{
163160
public:
@@ -294,12 +291,15 @@ class MapBasedPredictionNode : public rclcpp::Node
294291
const std::string & object_id, std::unordered_map<std::string, TrackedObject> & current_users);
295292
std::optional<size_t> searchProperStartingRefPathIndex(
296293
const TrackedObject & object, const PosePath & pose_path) const;
297-
std::vector<PredictedRefPath> getPredictedReferencePath(
294+
std::vector<LaneletPathWithPathInfo> getPredictedReferencePath(
298295
const TrackedObject & object, const LaneletsData & current_lanelets_data,
299296
const double object_detected_time, const double time_horizon);
297+
std::vector<PredictedRefPath> convertPredictedReferencePath(
298+
const TrackedObject & object,
299+
const std::vector<LaneletPathWithPathInfo> & lanelet_ref_paths) const;
300300
Maneuver predictObjectManeuver(
301-
const TrackedObject & object, const LaneletData & current_lanelet_data,
302-
const double object_detected_time);
301+
const std::string & object_id, const geometry_msgs::msg::Pose & object_pose,
302+
const LaneletData & current_lanelet_data, const double object_detected_time);
303303
geometry_msgs::msg::Pose compensateTimeDelay(
304304
const geometry_msgs::msg::Pose & delayed_pose, const geometry_msgs::msg::Twist & twist,
305305
const double dt) const;
@@ -308,24 +308,16 @@ class MapBasedPredictionNode : public rclcpp::Node
308308
double calcLeftLateralOffset(
309309
const lanelet::ConstLineString2d & boundary_line, const geometry_msgs::msg::Pose & search_pose);
310310
ManeuverProbability calculateManeuverProbability(
311-
const Maneuver & predicted_maneuver, const lanelet::routing::LaneletPaths & left_paths,
312-
const lanelet::routing::LaneletPaths & right_paths,
313-
const lanelet::routing::LaneletPaths & center_paths);
314-
315-
void addReferencePaths(
316-
const TrackedObject & object, const lanelet::routing::LaneletPaths & candidate_paths,
317-
const float path_probability, const ManeuverProbability & maneuver_probability,
318-
const Maneuver & maneuver, std::vector<PredictedRefPath> & reference_paths,
319-
const double speed_limit = 0.0);
320-
321-
mutable universe_utils::LRUCache<
322-
lanelet::routing::LaneletPaths, std::vector<std::pair<PosePath, double>>>
311+
const Maneuver & predicted_maneuver, const bool & left_paths_exists,
312+
const bool & right_paths_exists, const bool & center_paths_exists) const;
313+
314+
mutable universe_utils::LRUCache<lanelet::routing::LaneletPath, std::pair<PosePath, double>>
323315
lru_cache_of_convert_path_type_{1000};
324-
std::vector<std::pair<PosePath, double>> convertPathType(
325-
const lanelet::routing::LaneletPaths & paths) const;
316+
std::pair<PosePath, double> convertLaneletPathToPosePath(
317+
const lanelet::routing::LaneletPath & path) const;
326318

327319
void updateFuturePossibleLanelets(
328-
const TrackedObject & object, const lanelet::routing::LaneletPaths & paths);
320+
const std::string & object_id, const lanelet::routing::LaneletPaths & paths);
329321

330322
bool isDuplicated(
331323
const std::pair<double, lanelet::ConstLanelet> & target_lanelet,
@@ -342,11 +334,11 @@ class MapBasedPredictionNode : public rclcpp::Node
342334
const TrackedObject & object, const Maneuver & maneuver, const size_t obj_num);
343335

344336
Maneuver predictObjectManeuverByTimeToLaneChange(
345-
const TrackedObject & object, const LaneletData & current_lanelet_data,
337+
const std::string & object_id, const LaneletData & current_lanelet_data,
346338
const double object_detected_time);
347339
Maneuver predictObjectManeuverByLatDiffDistance(
348-
const TrackedObject & object, const LaneletData & current_lanelet_data,
349-
const double object_detected_time);
340+
const std::string & object_id, const geometry_msgs::msg::Pose & object_pose,
341+
const LaneletData & current_lanelet_data, const double object_detected_time);
350342

351343
void publish(
352344
const PredictedObjects & output,

0 commit comments

Comments
 (0)