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(start_planner): disable safety check against dynamic objects when ego polygon overlap with centerline #6236

Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,7 @@ class StartPlannerModule : public SceneModuleInterface

bool isModuleRunning() const;
bool isCurrentPoseOnMiddleOfTheRoad() const;
bool isOverlapWithCenterLane() const;
bool isCloseToOriginalStartPose() const;
bool hasArrivedAtGoal() const;
bool isMoving() const;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_start_planner_module/src/start_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 1227 to 1256, 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_start_planner_module/util.hpp"
#include "motion_utils/trajectory/trajectory.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <magic_enum.hpp>
Expand Down Expand Up @@ -211,7 +212,8 @@

bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const
{
return parameters_->safety_check_params.enable_safety_check && status_.driving_forward;
return parameters_->safety_check_params.enable_safety_check && status_.driving_forward &&
!isOverlapWithCenterLane();
}

bool StartPlannerModule::noMovingObjectsAround() const
Expand Down Expand Up @@ -278,6 +280,37 @@
return std::abs(lateral_distance_to_center_lane) < parameters_->th_distance_to_middle_of_the_road;
}

bool StartPlannerModule::isOverlapWithCenterLane() const
{
const Pose & current_pose = planner_data_->self_odometry->pose.pose;
const auto current_lanes = utils::getCurrentLanes(planner_data_);
const auto & local_vehicle_footprint = vehicle_info_.createFootprint();
const auto & vehicle_footprint =
transformVector(local_vehicle_footprint, tier4_autoware_utils::pose2transform(current_pose));
kyoichi-sugahara marked this conversation as resolved.
Show resolved Hide resolved
for (const auto & current_lane : current_lanes) {
std::vector<geometry_msgs::msg::Point> centerline_points;
for (const auto & point : current_lane.centerline()) {
geometry_msgs::msg::Point center_point = lanelet::utils::conversion::toGeomMsgPt(point);
centerline_points.push_back(center_point);
}

for (size_t i = 0; i < centerline_points.size() - 1; ++i) {
const auto & p1 = centerline_points.at(i);
const auto & p2 = centerline_points.at(i + 1);
for (size_t j = 0; j < vehicle_footprint.size() - 1; ++j) {
const auto & p3 = tier4_autoware_utils::toMsg(vehicle_footprint[j].to_3d());
const auto & p4 = tier4_autoware_utils::toMsg(vehicle_footprint[j + 1].to_3d());
kyoichi-sugahara marked this conversation as resolved.
Show resolved Hide resolved
const auto intersection = tier4_autoware_utils::intersect(p1, p2, p3, p4);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

how abount just check intersection of polygon and lines not giving 4 points

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe it is possible with boost geometry

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@kyoichi-sugahara said tier4 utils is fater

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@kosuke55
I'm using it because this computational cost is low


if (intersection.has_value()) {
return true;
}
}
}
}
return false;
}

Check warning on line 312 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

StartPlannerModule::isOverlapWithCenterLane has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested 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 312 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

StartPlannerModule::isOverlapWithCenterLane has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.

bool StartPlannerModule::isCloseToOriginalStartPose() const
{
const Pose start_pose = planner_data_->route_handler->getOriginalStartPose();
Expand Down Expand Up @@ -926,8 +959,8 @@
pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, 0,
std::numeric_limits<double>::max());

// Set the maximum backward distance less than the distance from the vehicle's base_link to the
// lane's rearmost point to prevent lane departure.
// Set the maximum backward distance less than the distance from the vehicle's base_link to
// the lane's rearmost point to prevent lane departure.
const double current_arc_length =
lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose).length;
const double allowed_backward_distance = std::clamp(
Expand Down Expand Up @@ -1215,8 +1248,8 @@
{
const auto & rh = planner_data_->route_handler;

// Check if the goal and ego are in the same route segment. If not, this is out of scope of this
// function. Return false.
// Check if the goal and ego are in the same route segment. If not, this is out of scope of
// this function. Return false.
lanelet::ConstLanelet ego_lanelet;
rh->getClosestLaneletWithinRoute(getEgoPose(), &ego_lanelet);
const auto is_ego_in_goal_route_section = rh->isInGoalRouteSection(ego_lanelet);
Expand Down
Loading