Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

perf(autoware_map_based_prediction): removed duplicate findNearest calculations #8490

Merged
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1991 to 1998, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 7.19 to 7.09, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -32,6 +32,7 @@

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/Lanelet.h>
#include <lanelet2_core/geometry/LaneletMap.h>
#include <lanelet2_core/geometry/Point.h>
#include <lanelet2_routing/RoutingGraph.h>
#include <tf2/utils.h>
Expand Down Expand Up @@ -360,17 +361,11 @@
}

bool withinRoadLanelet(
const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr,
const TrackedObject & object,
const std::vector<std::pair<double, lanelet::Lanelet>> & surrounding_lanelets_with_dist,
const bool use_yaw_information = false)
{
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y);
// nearest lanelet
constexpr double search_radius = 10.0; // [m]
const auto surrounding_lanelets =
lanelet::geometry::findNearest(lanelet_map_ptr->laneletLayer, search_point, search_radius);

for (const auto & lanelet_with_dist : surrounding_lanelets) {
for (const auto & lanelet_with_dist : surrounding_lanelets_with_dist) {
const auto & dist = lanelet_with_dist.first;
yhisaki marked this conversation as resolved.
Show resolved Hide resolved
const auto & lanelet = lanelet_with_dist.second;

Expand All @@ -397,6 +392,20 @@
return false;
}

bool withinRoadLanelet(
const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr,
const bool use_yaw_information = false)
{
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y);
// nearest lanelet
constexpr double search_radius = 10.0; // [m]
const auto surrounding_lanelets_with_dist =
lanelet::geometry::findWithin2D(lanelet_map_ptr->laneletLayer, search_point, search_radius);

return withinRoadLanelet(object, surrounding_lanelets_with_dist, use_yaw_information);
}

boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints(
const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets,
const lanelet::ConstLanelets & surrounding_crosswalks, const CrosswalkEdgePoints & edge_points,
Expand Down Expand Up @@ -1411,9 +1420,7 @@
const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear;
const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y);
const auto velocity = std::max(min_crosswalk_user_velocity_, estimated_velocity);
// TODO(Mamoru Sobue): 3rd argument of findNearest is the number of lanelets, not radius, so past
// implementation has been wrong.
const auto surrounding_lanelets_with_dist = lanelet::geometry::findNearest(
const auto surrounding_lanelets_with_dist = lanelet::geometry::findWithin2d(
lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y},
prediction_time_horizon_.pedestrian * velocity);
lanelet::ConstLanelets surrounding_lanelets;
Expand Down Expand Up @@ -1458,7 +1465,7 @@

// If the object is not crossing the crosswalk, in the road lanelets, try to find the closest
// crosswalk and generate path to the crosswalk edge
} else if (withinRoadLanelet(object, lanelet_map_ptr_)) {
} else if (withinRoadLanelet(object, surrounding_lanelets_with_dist)) {
lanelet::ConstLanelet closest_crosswalk{};
const auto & obj_pose = object.kinematics.pose_with_covariance.pose;
const auto found_closest_crosswalk =
Expand Down
Loading