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(avoidance): don't use polygon centroid in shiftable ratio calculation #6285

Merged
merged 2 commits into from
Feb 5, 2024
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
36 changes: 20 additions & 16 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/utils.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 1767 to 1771, 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.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -21,6 +21,7 @@
#include "behavior_path_planner_common/utils/traffic_light_utils.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>

Expand Down Expand Up @@ -483,108 +484,108 @@
bool isObjectOnRoadShoulder(
ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
const std::shared_ptr<AvoidanceParameters> & parameters)
{
using boost::geometry::return_centroid;
using boost::geometry::within;
using lanelet::geometry::distance2d;
using lanelet::geometry::toArcCoordinates;
using lanelet::utils::to2D;
using lanelet::utils::conversion::toLaneletPoint;

// assume that there are no parked vehicles in intersection.
std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else");
if (turn_direction == "right" || turn_direction == "left" || turn_direction == "straight") {
return false;
}

// ============================================ <- most_left_lanelet.leftBound()
// y road shoulder
// ^ ------------------------------------------
// | x +
// +---> --- object closest lanelet --- o ----- <- object_closest_lanelet.centerline()
//
// --------------------------------------------
// +: object position
// o: nearest point on centerline

lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y());

const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
const auto centerline_pose =
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position);
lanelet::BasicPoint3d centerline_point(
centerline_pose.position.x, centerline_pose.position.y, centerline_pose.position.z);
const auto centerline_pos =
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position).position;

bool is_left_side_parked_vehicle = false;
if (!isOnRight(object)) {
auto [object_shiftable_distance, sub_type] = [&]() {
const auto most_left_road_lanelet =
route_handler->getMostLeftLanelet(object.overhang_lanelet);
const auto most_left_lanelet_candidates =
route_handler->getLaneletMapPtr()->laneletLayer.findUsages(
most_left_road_lanelet.leftBound());

lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet;
const lanelet::Attribute sub_type =
most_left_lanelet.attribute(lanelet::AttributeName::Subtype);

for (const auto & ll : most_left_lanelet_candidates) {
const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype);
if (sub_type.value() == "road_shoulder") {
most_left_lanelet = ll;
}
}

const auto center_to_left_boundary =
distance2d(to2D(most_left_lanelet.leftBound().basicLineString()), to2D(centerline_point));
const auto center_to_left_boundary = distance2d(
to2D(most_left_lanelet.leftBound().basicLineString()),
to2D(toLaneletPoint(centerline_pos)).basicPoint());

return std::make_pair(
center_to_left_boundary - 0.5 * object.object.shape.dimensions.y, sub_type);
}();

if (sub_type.value() != "road_shoulder") {
object_shiftable_distance += parameters->object_check_min_road_shoulder_width;
}

const auto arc_coordinates = toArcCoordinates(
to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid);
to2D(object.overhang_lanelet.centerline().basicLineString()),
to2D(toLaneletPoint(object_pose.position)).basicPoint());
object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance;

is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio;
}

bool is_right_side_parked_vehicle = false;
if (isOnRight(object)) {
auto [object_shiftable_distance, sub_type] = [&]() {
const auto most_right_road_lanelet =
route_handler->getMostRightLanelet(object.overhang_lanelet);
const auto most_right_lanelet_candidates =
route_handler->getLaneletMapPtr()->laneletLayer.findUsages(
most_right_road_lanelet.rightBound());

lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet;
const lanelet::Attribute sub_type =
most_right_lanelet.attribute(lanelet::AttributeName::Subtype);

for (const auto & ll : most_right_lanelet_candidates) {
const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype);
if (sub_type.value() == "road_shoulder") {
most_right_lanelet = ll;
}
}

const auto center_to_right_boundary =
distance2d(to2D(most_right_lanelet.rightBound().basicLineString()), to2D(centerline_point));
const auto center_to_right_boundary = distance2d(
to2D(most_right_lanelet.rightBound().basicLineString()),
to2D(toLaneletPoint(centerline_pos)).basicPoint());

return std::make_pair(
center_to_right_boundary - 0.5 * object.object.shape.dimensions.y, sub_type);
}();

if (sub_type.value() != "road_shoulder") {
object_shiftable_distance += parameters->object_check_min_road_shoulder_width;
}

const auto arc_coordinates = toArcCoordinates(
to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid);
to2D(object.overhang_lanelet.centerline().basicLineString()),
to2D(toLaneletPoint(object_pose.position)).basicPoint());

Check warning on line 588 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

isObjectOnRoadShoulder already has high cyclomatic complexity, and now it increases in Lines of Code from 82 to 83. 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.
object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance;

is_right_side_parked_vehicle =
Expand Down Expand Up @@ -760,6 +761,8 @@
const std::shared_ptr<AvoidanceParameters> & parameters)
{
using boost::geometry::within;
using lanelet::utils::to2D;
using lanelet::utils::conversion::toLaneletPoint;

object.behavior = getObjectBehavior(object, parameters);
object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler);
Expand All @@ -770,9 +773,10 @@
}

// check vehicle shift ratio
lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y());
const auto on_ego_driving_lane =
within(object_centroid, object.overhang_lanelet.polygon2d().basicPolygon());
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
const auto on_ego_driving_lane = within(

Check warning on line 777 in planning/behavior_path_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/utils.cpp#L776-L777

Added lines #L776 - L777 were not covered by tests
to2D(toLaneletPoint(object_pos)).basicPoint(),
object.overhang_lanelet.polygon2d().basicPolygon());
if (on_ego_driving_lane) {
if (isObjectOnRoadShoulder(object, planner_data->route_handler, parameters)) {
return true;
Expand Down
Loading