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

feat(goal_planne): check objects within the area between ego edge and boudary of pull_over_lanes #6369

Merged
Show file tree
Hide file tree
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
Expand Up @@ -39,6 +39,8 @@
object_recognition_collision_check_max_extra_stopping_margin: 1.0
th_moving_object_velocity: 1.0
detection_bound_offset: 15.0
outer_road_detection_offset: 1.0
inner_road_detection_offset: 0.0

# pull over
pull_over:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -221,6 +221,7 @@ struct GoalPlannerDebugData
{
FreespacePlannerDebugData freespace_planner{};
std::vector<Polygon2d> ego_polygons_expanded{};
lanelet::ConstLanelet expanded_pull_over_lane_between_ego{};
};

struct LastApprovalData
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,8 @@ struct GoalPlannerParameters
double object_recognition_collision_check_max_extra_stopping_margin{0.0};
double th_moving_object_velocity{0.0};
double detection_bound_offset{0.0};
double outer_road_detection_offset{0.0};
double inner_road_detection_offset{0.0};

// pull over general params
double pull_over_minimum_request_length{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,19 @@ using visualization_msgs::msg::MarkerArray;
lanelet::ConstLanelets getPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance);

/*
* @brief expand pull_over_lanes to the opposite side of drivable roads by bound_offset.
* bound_offset must be positive regardless of left_side is true/false
*/
lanelet::ConstLanelets generateExpandedPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance, double bound_offset);
const double forward_distance, const double bound_offset);

lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes(
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side,
const geometry_msgs::msg::Pose ego_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
const double outer_road_offset, const double inner_road_offset);
PredictedObjects extractObjectsInExpandedPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance, double bound_offset, const PredictedObjects & objects);
Expand Down Expand Up @@ -85,6 +95,9 @@ MarkerArray createTextsMarkerArray(
const std::vector<Pose> & poses, std::string && ns, const std_msgs::msg::ColorRGBA & color);
MarkerArray createGoalCandidatesMarkerArray(
const GoalCandidates & goal_candidates, const std_msgs::msg::ColorRGBA & color);
MarkerArray createLaneletPolygonMarkerArray(
const lanelet::CompoundPolygon3d & polygon, const std_msgs::msg::Header & header,
const std::string & ns, const std_msgs::msg::ColorRGBA & color);
MarkerArray createNumObjectsToAvoidTextsMarkerArray(
const GoalCandidates & goal_candidates, std::string && ns,
const std_msgs::msg::ColorRGBA & color);
Expand Down
117 changes: 103 additions & 14 deletions planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp
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 planning/behavior_path_goal_planner_module/src/goal_planner_module.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 1590 to 1660, 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_path_goal_planner_module/src/goal_planner_module.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 4.82 to 4.91, 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 @@ -1867,6 +1867,50 @@
goal_planner_data_.ego_predicted_path = ego_predicted_path;
}

static std::vector<utils::path_safety_checker::ExtendedPredictedObject> filterObjectsByWithinPolicy(

Check warning on line 1870 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1870

Added line #L1870 was not covered by tests
const std::shared_ptr<const PredictedObjects> & objects,
const lanelet::ConstLanelets & target_lanes,
const std::shared_ptr<behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams> &
params)
{
// implanted part of behavior_path_planner::utils::path_safety_checker::filterObjects() and
// createTargetObjectsOnLane()

// Guard
if (objects->objects.empty()) {
return {};

Check warning on line 1881 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1880-L1881

Added lines #L1880 - L1881 were not covered by tests
}

const double ignore_object_velocity_threshold = params->ignore_object_velocity_threshold;
const auto & target_object_types = params->object_types_to_check;

Check warning on line 1885 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1884-L1885

Added lines #L1884 - L1885 were not covered by tests

PredictedObjects filtered_objects = utils::path_safety_checker::filterObjectsByVelocity(
*objects, ignore_object_velocity_threshold, false);

Check warning on line 1888 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1888

Added line #L1888 was not covered by tests

utils::path_safety_checker::filterObjectsByClass(filtered_objects, target_object_types);

Check warning on line 1890 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1890

Added line #L1890 was not covered by tests

std::vector<PredictedObject> within_filtered_objects;
for (const auto & target_lane : target_lanes) {
const auto lane_poly = target_lane.polygon2d().basicPolygon();
for (const auto & filtered_object : filtered_objects.objects) {
const auto object_bbox = tier4_autoware_utils::toPolygon2d(filtered_object);
if (boost::geometry::within(object_bbox, lane_poly)) {
within_filtered_objects.push_back(filtered_object);

Check warning on line 1898 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1893-L1898

Added lines #L1893 - L1898 were not covered by tests
}
}

Check warning on line 1900 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1900

Added line #L1900 was not covered by tests
}

const double safety_check_time_horizon = params->safety_check_time_horizon;
const double safety_check_time_resolution = params->safety_check_time_resolution;

Check warning on line 1904 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1903-L1904

Added lines #L1903 - L1904 were not covered by tests

std::vector<utils::path_safety_checker::ExtendedPredictedObject> refined_filtered_objects;
for (const auto & within_filtered_object : within_filtered_objects) {
refined_filtered_objects.push_back(utils::path_safety_checker::transform(

Check warning on line 1908 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1907-L1908

Added lines #L1907 - L1908 were not covered by tests
within_filtered_object, safety_check_time_horizon, safety_check_time_resolution));
}
return refined_filtered_objects;
}

Check warning on line 1912 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1912

Added line #L1912 was not covered by tests

std::pair<bool, bool> GoalPlannerModule::isSafePath() const
{
if (!thread_safe_data_.get_pull_over_path()) {
Expand Down Expand Up @@ -1904,31 +1948,67 @@
ego_predicted_path_params_, pull_over_path.points, current_pose, current_velocity,
ego_seg_idx, is_object_front, limit_to_max_velocity);

// filtering objects with velocity, position and class
const auto filtered_objects = utils::path_safety_checker::filterObjects(
dynamic_object, route_handler, pull_over_lanes, current_pose.position,
objects_filtering_params_);
// ==========================================================================================
// if ego is before the entry of pull_over_lanes, the beginning of the safety check area
// should be from the entry of pull_over_lanes
// ==========================================================================================
const Pose ego_pose_for_expand = std::invoke([&]() {

Check warning on line 1955 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1955

Added line #L1955 was not covered by tests
// get first road lane in pull over lanes segment
const auto fist_road_lane = std::invoke([&]() {
const auto first_pull_over_lane = pull_over_lanes.front();
if (!route_handler->isShoulderLanelet(first_pull_over_lane)) {

Check warning on line 1959 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1957-L1959

Added lines #L1957 - L1959 were not covered by tests
return first_pull_over_lane;
}
const auto road_lane_opt = left_side_parking_

Check warning on line 1962 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1962

Added line #L1962 was not covered by tests
? route_handler->getRightLanelet(first_pull_over_lane)
: route_handler->getLeftLanelet(first_pull_over_lane);
if (road_lane_opt) {

Check warning on line 1965 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1964-L1965

Added lines #L1964 - L1965 were not covered by tests
return road_lane_opt.value();
}
return first_pull_over_lane;
});

Check warning on line 1969 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1969

Added line #L1969 was not covered by tests
// generate first road lane pose
Pose first_road_pose{};
const auto first_road_point =
lanelet::utils::conversion::toGeomMsgPt(fist_road_lane.centerline().front());
const double lane_yaw = lanelet::utils::getLaneletAngle(fist_road_lane, first_road_point);
first_road_pose.position = first_road_point;
first_road_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(lane_yaw);

Check warning on line 1976 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1973-L1976

Added lines #L1973 - L1976 were not covered by tests
// if current ego pose is before pull over lanes segment, use first road lanelet center pose
if (
calcSignedArcLength(pull_over_path.points, first_road_pose.position, current_pose.position) <

Check warning on line 1979 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1978-L1979

Added lines #L1978 - L1979 were not covered by tests
0.0) {
return first_road_pose;

Check warning on line 1981 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1981

Added line #L1981 was not covered by tests
}
// if current ego pose is in pull over lanes segment, use current ego pose
return current_pose;

Check warning on line 1984 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1984

Added line #L1984 was not covered by tests
});

// filtering objects based on the current position's lane
const auto target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane(
pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_);

utils::parking_departure::updateSafetyCheckTargetObjectsData(
goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path);
const auto expanded_pull_over_lanes_between_ego =
goal_planner_utils::generateBetweenEgoAndExpandedPullOverLanes(
pull_over_lanes, left_side_parking_, ego_pose_for_expand,
planner_data_->parameters.vehicle_info, parameters_->outer_road_detection_offset,
parameters_->inner_road_detection_offset);

Check warning on line 1992 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1990-L1992

Added lines #L1990 - L1992 were not covered by tests
const auto merged_expanded_pull_over_lanes =
lanelet::utils::combineLaneletsShape(expanded_pull_over_lanes_between_ego);

Check warning on line 1994 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1994

Added line #L1994 was not covered by tests
debug_data_.expanded_pull_over_lane_between_ego = merged_expanded_pull_over_lanes;

const auto filtered_objects = filterObjectsByWithinPolicy(
dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params_);

Check warning on line 1998 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1997-L1998

Added lines #L1997 - L1998 were not covered by tests

const double hysteresis_factor =
prev_data_.safety_status.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate;

const bool current_is_safe = std::invoke([&]() {
if (parameters_->safety_check_params.method == "RSS") {
return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS(
pull_over_path, ego_predicted_path, target_objects_on_lane.on_current_lane,
goal_planner_data_.collision_check, planner_data_->parameters,
safety_check_params_->rss_params, objects_filtering_params_->use_all_predicted_path,
hysteresis_factor);
pull_over_path, ego_predicted_path, filtered_objects, goal_planner_data_.collision_check,
planner_data_->parameters, safety_check_params_->rss_params,
objects_filtering_params_->use_all_predicted_path, hysteresis_factor);

Check warning on line 2008 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2006-L2008

Added lines #L2006 - L2008 were not covered by tests
} else if (parameters_->safety_check_params.method == "integral_predicted_polygon") {
return utils::path_safety_checker::checkSafetyWithIntegralPredictedPolygon(
ego_predicted_path, vehicle_info_, target_objects_on_lane.on_current_lane,
ego_predicted_path, vehicle_info_, filtered_objects,

Check warning on line 2011 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

GoalPlannerModule::isSafePath increases in cyclomatic complexity from 9 to 13, 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.

Check warning on line 2011 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2011

Added line #L2011 was not covered by tests
objects_filtering_params_->check_all_predicted_path,
parameters_->safety_check_params.integral_predicted_polygon_params,
goal_planner_data_.collision_check);
Expand Down Expand Up @@ -2046,6 +2126,15 @@
}
debug_marker_.markers.push_back(marker);

if (parameters_->safety_check_params.enable_safety_check) {
tier4_autoware_utils::appendMarkerArray(
goal_planner_utils::createLaneletPolygonMarkerArray(
debug_data_.expanded_pull_over_lane_between_ego.polygon3d(), header,

Check warning on line 2132 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2129-L2132

Added lines #L2129 - L2132 were not covered by tests
"expanded_pull_over_lane_between_ego",
tier4_autoware_utils::createMarkerColor(1.0, 0.7, 0.0, 0.999)),

Check warning on line 2134 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2134

Added line #L2134 was not covered by tests
&debug_marker_);
}

Check warning on line 2137 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

GoalPlannerModule::setDebugData increases in cyclomatic complexity from 25 to 26, 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.
// Visualize debug poses
const auto & debug_poses = thread_safe_data_.get_pull_over_path()->debug_poses;
for (size_t i = 0; i < debug_poses.size(); ++i) {
Expand Down
4 changes: 4 additions & 0 deletions planning/behavior_path_goal_planner_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,10 @@
ns + "object_recognition_collision_check_max_extra_stopping_margin");
p.th_moving_object_velocity = node->declare_parameter<double>(ns + "th_moving_object_velocity");
p.detection_bound_offset = node->declare_parameter<double>(ns + "detection_bound_offset");
p.outer_road_detection_offset =
node->declare_parameter<double>(ns + "outer_road_detection_offset");
p.inner_road_detection_offset =
node->declare_parameter<double>(ns + "inner_road_detection_offset");

Check warning on line 108 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

GoalPlannerModuleManager::init increases from 323 to 327 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 108 in planning/behavior_path_goal_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/manager.cpp#L105-L108

Added lines #L105 - L108 were not covered by tests
}

// pull over general params
Expand Down
69 changes: 67 additions & 2 deletions planning/behavior_path_goal_planner_module/src/util.cpp
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 planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 44.83% to 43.66%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -17,6 +17,7 @@
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -78,13 +79,62 @@

lanelet::ConstLanelets generateExpandedPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance, double bound_offset)
const double forward_distance, const double bound_offset)
{
const auto pull_over_lanes =
getPullOverLanes(route_handler, left_side, backward_distance, forward_distance);

return left_side ? lanelet::utils::getExpandedLanelets(pull_over_lanes, bound_offset, 0.0)
: lanelet::utils::getExpandedLanelets(pull_over_lanes, 0.0, bound_offset);
: lanelet::utils::getExpandedLanelets(pull_over_lanes, 0.0, -bound_offset);
}

Check warning on line 89 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L88-L89

Added lines #L88 - L89 were not covered by tests

static double getOffsetToLanesBoundary(

Check warning on line 91 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L91

Added line #L91 was not covered by tests
const lanelet::ConstLanelets & lanelet_sequence, const geometry_msgs::msg::Pose target_pose,
const bool left_side)
{
lanelet::ConstLanelet closest_lanelet;
lanelet::utils::query::getClosestLanelet(lanelet_sequence, target_pose, &closest_lanelet);

Check warning on line 96 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L95-L96

Added lines #L95 - L96 were not covered by tests

// the boundary closer to ego. if left_side, take right boundary
const auto & boundary3d = left_side ? closest_lanelet.rightBound() : closest_lanelet.leftBound();

Check warning on line 99 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L99

Added line #L99 was not covered by tests
const auto boundary = lanelet::utils::to2D(boundary3d);
using lanelet::utils::conversion::toLaneletPoint;
const auto arc_coords = lanelet::geometry::toArcCoordinates(
boundary, lanelet::utils::to2D(toLaneletPoint(target_pose.position)).basicPoint());
return arc_coords.distance;

Check warning on line 104 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L102-L104

Added lines #L102 - L104 were not covered by tests
}
soblin marked this conversation as resolved.
Show resolved Hide resolved

lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes(

Check warning on line 107 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L107

Added line #L107 was not covered by tests
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side,
const geometry_msgs::msg::Pose ego_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
const double outer_road_offset, const double inner_road_offset)
{
const double front_overhang = vehicle_info.front_overhang_m,
wheel_base = vehicle_info.wheel_base_m, wheel_tread = vehicle_info.wheel_tread_m;

Check warning on line 113 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L112-L113

Added lines #L112 - L113 were not covered by tests
const double side_overhang =
left_side ? vehicle_info.left_overhang_m : vehicle_info.right_overhang_m;
const double ego_length_to_front = wheel_base + front_overhang;

Check warning on line 116 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L115-L116

Added lines #L115 - L116 were not covered by tests
const double ego_width_to_front =
!left_side ? (-wheel_tread / 2.0 - side_overhang) : (wheel_tread / 2.0 + side_overhang);

Check warning on line 118 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L118

Added line #L118 was not covered by tests
tier4_autoware_utils::Point2d front_edge_local{ego_length_to_front, ego_width_to_front};
const auto front_edge_glob = tier4_autoware_utils::transformPoint(
front_edge_local, tier4_autoware_utils::pose2transform(ego_pose));

Check warning on line 121 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L121

Added line #L121 was not covered by tests
geometry_msgs::msg::Pose ego_front_pose;
ego_front_pose.position =
createPoint(front_edge_glob.x(), front_edge_glob.y(), ego_pose.position.z);

Check warning on line 124 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L124

Added line #L124 was not covered by tests

// ==========================================================================================
// NOTE: the point which is on the right side of a directed line has negative distance
// getExpandedLanelet(1.0, -2.0) expands a lanelet by 1.0 to the left and by 2.0 to the right
// ==========================================================================================
const double ego_offset_to_closer_boundary =
getOffsetToLanesBoundary(pull_over_lanes, ego_front_pose, left_side);

Check warning on line 131 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L131

Added line #L131 was not covered by tests
return left_side ? lanelet::utils::getExpandedLanelets(
pull_over_lanes, outer_road_offset,
ego_offset_to_closer_boundary - inner_road_offset)
: lanelet::utils::getExpandedLanelets(
pull_over_lanes, ego_offset_to_closer_boundary + inner_road_offset,
-outer_road_offset);

Check notice on line 137 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Excess Number of Function Arguments

generateBetweenEgoAndExpandedPullOverLanes has 6 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.

Check warning on line 137 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L137

Added line #L137 was not covered by tests
}

PredictedObjects extractObjectsInExpandedPullOverLanes(
Expand Down Expand Up @@ -233,6 +283,21 @@
return marker_array;
}

MarkerArray createLaneletPolygonMarkerArray(

Check warning on line 286 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L286

Added line #L286 was not covered by tests
const lanelet::CompoundPolygon3d & polygon, const std_msgs::msg::Header & header,
const std::string & ns, const std_msgs::msg::ColorRGBA & color)
{
visualization_msgs::msg::MarkerArray marker_array{};
auto marker = createDefaultMarker(
header.frame_id, header.stamp, ns, 0, visualization_msgs::msg::Marker::LINE_STRIP,
createMarkerScale(0.1, 0.0, 0.0), color);
for (const auto & p : polygon) {
marker.points.push_back(createPoint(p.x(), p.y(), p.z()));

Check warning on line 295 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L292-L295

Added lines #L292 - L295 were not covered by tests
}
marker_array.markers.push_back(marker);
return marker_array;
}

Check warning on line 299 in planning/behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/util.cpp#L297-L299

Added lines #L297 - L299 were not covered by tests

double calcLateralDeviationBetweenPaths(
const PathWithLaneId & reference_path, const PathWithLaneId & target_path)
{
Expand Down
Loading