Skip to content

Commit 5fa0141

Browse files
refactor(lane_change): separate path-related function to utils/path (#9633)
* refactor(lane_change): separate path-related function to utils/path Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * remove old terminal lane change computation Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * doxygen comments Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * remove frenet planner header Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * minor refactoring by throwing instead Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * minor refactoring Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix docstring and remove redundant argument Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * get logger in header Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * add docstring Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * rename function is_colliding Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Fix failing test Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix for failing scenario caused by prepare velocity Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix error message Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent daa8a15 commit 5fa0141

File tree

10 files changed

+561
-667
lines changed

10 files changed

+561
-667
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
1212
src/utils/calculation.cpp
1313
src/utils/markers.cpp
1414
src/utils/utils.cpp
15+
src/utils/path.cpp
1516
)
1617

1718
if(BUILD_TESTING)

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp

-5
Original file line numberDiff line numberDiff line change
@@ -102,8 +102,6 @@ class LaneChangeBase
102102

103103
virtual LaneChangePath getLaneChangePath() const = 0;
104104

105-
virtual BehaviorModuleOutput getTerminalLaneChangePath() const = 0;
106-
107105
virtual bool isEgoOnPreparePhase() const = 0;
108106

109107
virtual bool isRequiredStop(const bool is_trailing_object) = 0;
@@ -235,9 +233,6 @@ class LaneChangeBase
235233
protected:
236234
virtual int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const = 0;
237235

238-
virtual bool get_prepare_segment(
239-
PathWithLaneId & prepare_segment, const double prepare_length) const = 0;
240-
241236
virtual bool isValidPath(const PathWithLaneId & path) const = 0;
242237

243238
virtual bool isAbleToStopSafely() const = 0;

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp

+3-45
Original file line numberDiff line numberDiff line change
@@ -64,8 +64,6 @@ class NormalLaneChange : public LaneChangeBase
6464

6565
LaneChangePath getLaneChangePath() const override;
6666

67-
BehaviorModuleOutput getTerminalLaneChangePath() const override;
68-
6967
BehaviorModuleOutput generateOutput() override;
7068

7169
void extendOutputDrivableArea(BehaviorModuleOutput & output) const override;
@@ -128,47 +126,26 @@ class NormalLaneChange : public LaneChangeBase
128126

129127
void filterOncomingObjects(PredictedObjects & objects) const;
130128

131-
bool get_prepare_segment(
132-
PathWithLaneId & prepare_segment, const double prepare_length) const override;
133-
134-
PathWithLaneId getTargetSegment(
135-
const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose,
136-
const double target_lane_length, const double lane_changing_length,
137-
const double lane_changing_velocity, const double buffer_for_next_lane_change) const;
138-
139129
std::vector<LaneChangePhaseMetrics> get_prepare_metrics() const;
140130
std::vector<LaneChangePhaseMetrics> get_lane_changing_metrics(
141131
const PathWithLaneId & prep_segment, const LaneChangePhaseMetrics & prep_metrics,
142132
const double shift_length, const double dist_to_reg_element) const;
143133

144134
bool get_lane_change_paths(LaneChangePaths & candidate_paths) const;
145135

146-
LaneChangePath get_candidate_path(
147-
const LaneChangePhaseMetrics & prep_metrics, const LaneChangePhaseMetrics & lc_metrics,
148-
const PathWithLaneId & prep_segment, const std::vector<std::vector<int64_t>> & sorted_lane_ids,
149-
const Pose & lc_start_pose, const double shift_length) const;
150-
151136
bool check_candidate_path_safety(
152137
const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const;
153138

154-
std::optional<LaneChangePath> calcTerminalLaneChangePath(
155-
const lanelet::ConstLanelets & current_lanes,
156-
const lanelet::ConstLanelets & target_lanes) const;
157-
158139
bool isValidPath(const PathWithLaneId & path) const override;
159140

160141
PathSafetyStatus isLaneChangePathSafe(
161142
const LaneChangePath & lane_change_path,
143+
const std::vector<std::vector<PoseWithVelocityStamped>> & ego_predicted_paths,
162144
const lane_change::TargetObjects & collision_check_objects,
163145
const utils::path_safety_checker::RSSparams & rss_params,
164-
const size_t deceleration_sampling_num, CollisionCheckDebugMap & debug_data) const;
165-
166-
bool has_collision_with_decel_patterns(
167-
const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & objects,
168-
const size_t deceleration_sampling_num, const RSSparams & rss_param,
169-
const bool check_prepare_phase, CollisionCheckDebugMap & debug_data) const;
146+
CollisionCheckDebugMap & debug_data) const;
170147

171-
bool is_collided(
148+
bool is_colliding(
172149
const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj,
173150
const std::vector<PoseWithVelocityStamped> & ego_predicted_path,
174151
const RSSparams & selected_rss_param, const bool check_prepare_phase,
@@ -178,24 +155,6 @@ class NormalLaneChange : public LaneChangeBase
178155

179156
bool is_ego_stuck() const;
180157

181-
/**
182-
* @brief Checks if the given pose is a valid starting point for a lane change.
183-
*
184-
* This function determines whether the given pose (position) of the vehicle is within
185-
* the area of either the target neighbor lane or the target lane itself. It uses geometric
186-
* checks to see if the start point of the lane change is covered by the polygons representing
187-
* these lanes.
188-
*
189-
* @param common_data_ptr Shared pointer to a CommonData structure, which should include:
190-
* - Non-null `lanes_polygon_ptr` that contains the polygon data for lanes.
191-
* @param pose The current pose of the vehicle
192-
*
193-
* @return `true` if the pose is within either the target neighbor lane or the target lane;
194-
* `false` otherwise.
195-
*/
196-
bool is_valid_start_point(
197-
const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const;
198-
199158
bool check_prepare_phase() const;
200159

201160
void set_stop_pose(const double arc_length_to_stop_pose, PathWithLaneId & path);
@@ -213,7 +172,6 @@ class NormalLaneChange : public LaneChangeBase
213172

214173
std::vector<PathPointWithLaneId> path_after_intersection_;
215174
double stop_time_{0.0};
216-
static constexpr double floating_err_th{1e-3};
217175
};
218176
} // namespace autoware::behavior_path_planner
219177
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -160,6 +160,8 @@ struct TargetObjects
160160
: leading(std::move(leading)), trailing(std::move(trailing))
161161
{
162162
}
163+
164+
[[nodiscard]] bool empty() const { return leading.empty() && trailing.empty(); }
163165
};
164166

165167
enum class ModuleType {
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,102 @@
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+
#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_
16+
#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_
17+
18+
#include "autoware/behavior_path_lane_change_module/structs/data.hpp"
19+
#include "autoware/behavior_path_lane_change_module/structs/path.hpp"
20+
21+
#include <autoware/behavior_path_planner_common/utils/utils.hpp>
22+
23+
#include <vector>
24+
25+
namespace autoware::behavior_path_planner::utils::lane_change
26+
{
27+
using behavior_path_planner::LaneChangePath;
28+
using behavior_path_planner::lane_change::CommonDataPtr;
29+
30+
/**
31+
* @brief Generates a prepare segment for a lane change maneuver.
32+
*
33+
* This function generates the "prepare segment" of the path by trimming it to the specified length,
34+
* adjusting longitudinal velocity for acceleration or deceleration, and ensuring the starting point
35+
* meets necessary constraints for a lane change.
36+
*
37+
* @param common_data_ptr Shared pointer to CommonData containing current and target lane
38+
* information, vehicle parameters, and ego state.
39+
* @param prev_module_path The input path from the previous module, which will be used
40+
* as the base for the prepare segment.
41+
* @param prep_metric Preparation metrics containing desired length and velocity for the segment.
42+
* @param prepare_segment Output parameter where the resulting prepare segment path will be stored.
43+
*
44+
* @throws std::logic_error If the lane change start point is behind the target lanelet or
45+
* if lane information is invalid.
46+
*
47+
* @return true if the prepare segment is successfully generated, false otherwise.
48+
*/
49+
bool get_prepare_segment(
50+
const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path,
51+
const LaneChangePhaseMetrics prep_metric, PathWithLaneId & prepare_segment);
52+
53+
/**
54+
* @brief Generates the candidate path for a lane change maneuver.
55+
*
56+
* This function calculates the candidate lane change path based on the provided preparation
57+
* and lane change metrics. It resamples the target lane reference path, determines the start
58+
* and end poses for the lane change, and constructs the shift line required for the maneuver.
59+
* The function ensures that the resulting path satisfies length and distance constraints.
60+
*
61+
* @param common_data_ptr Shared pointer to CommonData containing route, lane, and transient data.
62+
* @param prep_metric Metrics for the preparation phase, including path length and velocity.
63+
* @param lc_metric Metrics for the lane change phase, including path length and velocity.
64+
* @param prep_segment The path segment prepared before initiating the lane change.
65+
* @param sorted_lane_ids A vector of sorted lane IDs used for updating lane information in the
66+
* path.
67+
* @param lc_start_pose The pose where the lane change begins.
68+
* @param shift_length The lateral distance to shift during the lane change maneuver.
69+
*
70+
* @throws std::logic_error If the target lane reference path is empty, candidate path generation
71+
* fails, or the resulting path length exceeds terminal constraints.
72+
*
73+
* @return LaneChangePath The constructed candidate lane change path.
74+
*/
75+
LaneChangePath get_candidate_path(
76+
const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prep_metric,
77+
const LaneChangePhaseMetrics & lc_metric, const PathWithLaneId & prep_segment,
78+
const std::vector<std::vector<int64_t>> & sorted_lane_ids, const double shift_length);
79+
80+
/**
81+
* @brief Constructs a candidate path for a lane change maneuver.
82+
*
83+
* This function generates a candidate lane change path by shifting the target lane's reference path
84+
* and combining it with the prepare segment. It verifies the path's validity by checking the yaw
85+
* difference, adjusting longitudinal velocity, and updating lane IDs based on the provided lane
86+
* sorting information.
87+
*
88+
* @param lane_change_info Information about the lane change, including shift line and target
89+
* velocity.
90+
* @param prepare_segment The path segment leading up to the lane change.
91+
* @param target_lane_reference_path The reference path of the target lane.
92+
* @param sorted_lane_ids A vector of sorted lane IDs used to update the candidate path's lane IDs.
93+
*
94+
* @return std::optional<LaneChangePath> The constructed candidate path if valid, or std::nullopt
95+
* if the path fails any constraints.
96+
*/
97+
LaneChangePath construct_candidate_path(
98+
const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment,
99+
const PathWithLaneId & target_lane_reference_path,
100+
const std::vector<std::vector<int64_t>> & sorted_lane_ids);
101+
} // namespace autoware::behavior_path_planner::utils::lane_change
102+
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_

0 commit comments

Comments
 (0)