Skip to content

Commit 9f7a103

Browse files
fix(lane_change): skip path computation if len exceed dist to terminal start (autowarefoundation#8359)
Skip computation if prepare length exceed distance to terminal start Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent f064f0e commit 9f7a103

File tree

4 files changed

+104
-1
lines changed

4 files changed

+104
-1
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
99
src/interface.cpp
1010
src/manager.cpp
1111
src/scene.cpp
12+
src/utils/calculation.cpp
1213
src/utils/markers.cpp
1314
src/utils/utils.cpp
1415
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
15+
#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
16+
17+
#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp"
18+
19+
namespace autoware::behavior_path_planner::utils::lane_change::calculation
20+
{
21+
using behavior_path_planner::lane_change::CommonDataPtr;
22+
23+
/**
24+
* @brief Calculates the distance from the ego vehicle to the terminal point.
25+
*
26+
* This function computes the distance from the current position of the ego vehicle
27+
* to either the goal pose or the end of the current lane, depending on whether
28+
* the vehicle's current lane is within the goal section.
29+
*
30+
* @param common_data_ptr Shared pointer to a CommonData structure, which should include:
31+
* - Non null `lanes_ptr` that points to the current lanes data.
32+
* - Non null `self_odometry_ptr` that contains the current pose of the ego vehicle.
33+
* - Non null `route_handler_ptr` that contains the goal pose of the route.
34+
*
35+
* @return The distance to the terminal point (either the goal pose or the end of the current lane)
36+
* in meters.
37+
*/
38+
double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr);
39+
40+
double calc_dist_from_pose_to_terminal_end(
41+
const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes,
42+
const Pose & src_pose);
43+
} // namespace autoware::behavior_path_planner::utils::lane_change::calculation
44+
45+
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+13-1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
#include "autoware/behavior_path_lane_change_module/scene.hpp"
1616

17+
#include "autoware/behavior_path_lane_change_module/utils/calculation.hpp"
1718
#include "autoware/behavior_path_lane_change_module/utils/utils.hpp"
1819
#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
1920
#include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
@@ -45,6 +46,7 @@ using utils::lane_change::calcMinimumLaneChangeLength;
4546
using utils::lane_change::create_lanes_polygon;
4647
using utils::path_safety_checker::isPolygonOverlapLanelet;
4748
using utils::traffic_light::getDistanceToNextTrafficLight;
49+
namespace calculation = utils::lane_change::calculation;
4850

4951
NormalLaneChange::NormalLaneChange(
5052
const std::shared_ptr<LaneChangeParameters> & parameters, LaneChangeModuleType type,
@@ -1361,7 +1363,7 @@ bool NormalLaneChange::getLaneChangePaths(
13611363
route_handler.getLateralIntervalsToPreferredLane(target_lanes.back()));
13621364

13631365
const auto dist_to_end_of_current_lanes =
1364-
utils::getDistanceToEndOfLane(getEgoPose(), current_lanes);
1366+
calculation::calc_ego_dist_to_terminal_end(common_data_ptr_);
13651367

13661368
const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes);
13671369

@@ -1402,6 +1404,16 @@ bool NormalLaneChange::getLaneChangePaths(
14021404
const auto prepare_length = utils::lane_change::calcPhaseLength(
14031405
current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration);
14041406

1407+
const auto ego_dist_to_terminal_start = dist_to_end_of_current_lanes - lane_change_buffer;
1408+
if (prepare_length > ego_dist_to_terminal_start) {
1409+
RCLCPP_DEBUG(
1410+
logger_,
1411+
"Reject: Prepare length exceed distance to terminal start. prep_len: %.5f, ego dist to "
1412+
"terminal start: %.5f",
1413+
prepare_length, ego_dist_to_terminal_start);
1414+
continue;
1415+
}
1416+
14051417
auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length);
14061418

14071419
const auto debug_print = [&](const auto & s) {
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <autoware/behavior_path_lane_change_module/utils/calculation.hpp>
16+
#include <autoware/behavior_path_planner_common/utils/utils.hpp>
17+
18+
namespace autoware::behavior_path_planner::utils::lane_change::calculation
19+
{
20+
double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr)
21+
{
22+
const auto & lanes_ptr = common_data_ptr->lanes_ptr;
23+
const auto & current_lanes = lanes_ptr->current;
24+
const auto & current_pose = common_data_ptr->get_ego_pose();
25+
26+
return calc_dist_from_pose_to_terminal_end(common_data_ptr, current_lanes, current_pose);
27+
}
28+
29+
double calc_dist_from_pose_to_terminal_end(
30+
const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes,
31+
const Pose & src_pose)
32+
{
33+
if (lanes.empty()) {
34+
return 0.0;
35+
}
36+
37+
const auto & lanes_ptr = common_data_ptr->lanes_ptr;
38+
const auto & goal_pose = common_data_ptr->route_handler_ptr->getGoalPose();
39+
40+
if (lanes_ptr->current_lane_in_goal_section) {
41+
return utils::getSignedDistance(src_pose, goal_pose, lanes);
42+
}
43+
return utils::getDistanceToEndOfLane(src_pose, lanes);
44+
}
45+
} // namespace autoware::behavior_path_planner::utils::lane_change::calculation

0 commit comments

Comments
 (0)