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

fix(autoware_map_based_prediction): use surrounding_crosswalks instead of external_surrounding_crosswalks #8467

Merged
Merged
Changes from all 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 1955 to 1957, 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 worse: Overall Code Complexity

The mean cyclomatic complexity increases from 6.58 to 6.63, 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 @@ -411,8 +411,8 @@

boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints(
const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets,
const lanelet::ConstLanelets & external_surrounding_crosswalks,
const CrosswalkEdgePoints & edge_points, const double time_horizon, const double min_object_vel)
const lanelet::ConstLanelets & surrounding_crosswalks, const CrosswalkEdgePoints & edge_points,
const double time_horizon, const double min_object_vel)
{
using Point = boost::geometry::model::d2::point_xy<double>;

Expand All @@ -439,10 +439,10 @@
const auto is_stop_object = estimated_velocity < stop_velocity_th;
const auto velocity = std::max(min_object_vel, estimated_velocity);

const auto isAcrossAnyRoad = [&surrounding_lanelets, &external_surrounding_crosswalks](
const auto isAcrossAnyRoad = [&surrounding_lanelets, &surrounding_crosswalks](

Check warning on line 442 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp#L442

Added line #L442 was not covered by tests
const Point & p_src, const Point & p_dst) {
const auto withinAnyCrosswalk = [&external_surrounding_crosswalks](const Point & p) {
for (const auto & crosswalk : external_surrounding_crosswalks) {
const auto withinAnyCrosswalk = [&surrounding_crosswalks](const Point & p) {

Check warning on line 444 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp#L444

Added line #L444 was not covered by tests
for (const auto & crosswalk : surrounding_crosswalks) {
if (boost::geometry::within(p, crosswalk.polygon2d().basicPolygon())) {
return true;
}
Expand Down Expand Up @@ -1388,82 +1388,84 @@
lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y},
prediction_time_horizon_.pedestrian * velocity);
lanelet::ConstLanelets surrounding_lanelets;
lanelet::ConstLanelets external_surrounding_crosswalks;
lanelet::ConstLanelets surrounding_crosswalks;
for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) {
surrounding_lanelets.push_back(lanelet);
const auto attr = lanelet.attribute(lanelet::AttributeName::Subtype);
if (
attr.value() == lanelet::AttributeValueString::Crosswalk ||
attr.value() == lanelet::AttributeValueString::Walkway) {
const auto & crosswalk = lanelet;
surrounding_crosswalks.push_back(crosswalk);
if (withinLanelet(object, crosswalk)) {
crossing_crosswalk = crosswalk;
} else {
external_surrounding_crosswalks.push_back(crosswalk);
}
}
}

// If the object is in the crosswalk, generate path to the crosswalk edge
if (crossing_crosswalk) {
const auto edge_points = getCrosswalkEdgePoints(crossing_crosswalk.get());

if (hasPotentialToReach(
object, edge_points.front_center_point, edge_points.front_right_point,
edge_points.front_left_point, std::numeric_limits<double>::max(),
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) {
PredictedPath predicted_path =
path_generator_->generatePathToTargetPoint(object, edge_points.front_center_point);
predicted_path.confidence = 1.0;
predicted_object.kinematics.predicted_paths.push_back(predicted_path);
}

if (hasPotentialToReach(
object, edge_points.back_center_point, edge_points.back_right_point,
edge_points.back_left_point, std::numeric_limits<double>::max(),
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) {
PredictedPath predicted_path =
path_generator_->generatePathToTargetPoint(object, edge_points.back_center_point);
predicted_path.confidence = 1.0;
predicted_object.kinematics.predicted_paths.push_back(predicted_path);
}

// 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_)) {
lanelet::ConstLanelet closest_crosswalk{};
const auto & obj_pose = object.kinematics.pose_with_covariance.pose;
const auto found_closest_crosswalk =
lanelet::utils::query::getClosestLanelet(crosswalks_, obj_pose, &closest_crosswalk);

if (found_closest_crosswalk) {
const auto edge_points = getCrosswalkEdgePoints(closest_crosswalk);

if (hasPotentialToReach(
object, edge_points.front_center_point, edge_points.front_right_point,
edge_points.front_left_point, prediction_time_horizon_.pedestrian * 2.0,
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) {
PredictedPath predicted_path =
path_generator_->generatePathToTargetPoint(object, edge_points.front_center_point);
predicted_path.confidence = 1.0;
predicted_object.kinematics.predicted_paths.push_back(predicted_path);
}

if (hasPotentialToReach(
object, edge_points.back_center_point, edge_points.back_right_point,
edge_points.back_left_point, prediction_time_horizon_.pedestrian * 2.0,
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) {
PredictedPath predicted_path =
path_generator_->generatePathToTargetPoint(object, edge_points.back_center_point);
predicted_path.confidence = 1.0;
predicted_object.kinematics.predicted_paths.push_back(predicted_path);
}
}
}

// try to find the edge points for other surrounding crosswalks and generate path to the crosswalk
// edge
for (const auto & crosswalk : external_surrounding_crosswalks) {
for (const auto & crosswalk : surrounding_crosswalks) {
if (crossing_crosswalk && crossing_crosswalk.get() == crosswalk) {
yuki-takagi-66 marked this conversation as resolved.
Show resolved Hide resolved
continue;

Check warning on line 1467 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp#L1467

Added line #L1467 was not covered by tests
}
const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk);
if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) {
if (!calcIntentionToCrossWithTrafficSignal(
Expand All @@ -1488,7 +1490,7 @@
}

const auto reachable_crosswalk = isReachableCrosswalkEdgePoints(
object, surrounding_lanelets, external_surrounding_crosswalks, edge_points,
object, surrounding_lanelets, surrounding_crosswalks, edge_points,

Check warning on line 1493 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: Bumpy Road Ahead

MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser increases from 4 to 5 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check warning on line 1493 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: Complex Method

MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser increases in cyclomatic complexity from 27 to 30, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
prediction_time_horizon_.pedestrian, min_crosswalk_user_velocity_);

if (!reachable_crosswalk) {
Expand Down
Loading