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(crosswalk): fix passing direction calclation for the objects #9071

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 2020-2023 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1086 to 1081, 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 planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.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 6.05 to 6.00, 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 @@ -353,13 +353,16 @@
if (collision_state != CollisionState::YIELD) {
continue;
}

if (
isVehicleType(object.classification) && ego_crosswalk_passage_direction &&
collision_point.crosswalk_passage_direction) {
const double direction_diff = autoware::universe_utils::normalizeRadian(
double direction_diff = std::abs(std::fmod(

Check warning on line 360 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp#L360

Added line #L360 was not covered by tests
collision_point.crosswalk_passage_direction.value() -
ego_crosswalk_passage_direction.value());
if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) {
ego_crosswalk_passage_direction.value(),
M_PI_2));

Check warning on line 363 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp#L363

Added line #L363 was not covered by tests
direction_diff = std::min(direction_diff, M_PI_2 - direction_diff);
if (direction_diff < planner_param_.vehicle_object_cross_angle_threshold) {
continue;
}
}
Expand Down Expand Up @@ -670,8 +673,8 @@
std::optional<double> CrosswalkModule::findEgoPassageDirectionAlongPath(
const PathWithLaneId & path) const
{
auto findIntersectPoint = [&](const lanelet::ConstLineString3d line)
-> std::optional<std::pair<size_t, geometry_msgs::msg::Point>> {
auto findIntersectPoint =
[&](const lanelet::ConstLineString3d line) -> std::optional<geometry_msgs::msg::Point> {

Check warning on line 677 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp#L677

Added line #L677 was not covered by tests
const auto line_start =
autoware::universe_utils::createPoint(line.front().x(), line.front().y(), line.front().z());
const auto line_end =
Expand All @@ -682,29 +685,19 @@
if (const auto intersect =
autoware::universe_utils::intersect(line_start, line_end, start, end);
intersect.has_value()) {
return std::make_optional(std::make_pair(i, intersect.value()));
return intersect;

Check warning on line 688 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp#L688

Added line #L688 was not covered by tests
}
}
return std::nullopt;
};
const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound());
const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound());
const auto pt1 = findIntersectPoint(crosswalk_.leftBound());
const auto pt2 = findIntersectPoint(crosswalk_.rightBound());

if (!intersect_pt1 || !intersect_pt2) {
if (!pt1 || !pt2) {
return std::nullopt;
}

const auto idx1 = intersect_pt1.value().first;
const auto idx2 = intersect_pt2.value().first;

const auto min_idx = std::min(idx1, idx2);
const auto dist1 = calcSignedArcLength(path.points, min_idx, intersect_pt1.value().second);
const auto dist2 = calcSignedArcLength(path.points, min_idx, intersect_pt2.value().second);

const auto & front = dist1 > dist2 ? intersect_pt2.value().second : intersect_pt1.value().second;
const auto & back = dist1 > dist2 ? intersect_pt1.value().second : intersect_pt2.value().second;

return std::atan2(back.y - front.y, back.x - front.x);
return std::atan2(pt2->y - pt1->y, pt2->x - pt1->x);

Check warning on line 700 in planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp#L700

Added line #L700 was not covered by tests
}

std::optional<double> CrosswalkModule::findObjectPassageDirectionAlongVehicleLane(
Expand Down
Loading