Skip to content

Commit 881afe1

Browse files
refactor
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent d99d385 commit 881afe1

File tree

6 files changed

+123
-82
lines changed

6 files changed

+123
-82
lines changed

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

+9-1
Original file line numberDiff line numberDiff line change
@@ -136,7 +136,15 @@ class NormalLaneChange : public LaneChangeBase
136136

137137
bool get_path_using_frenet(
138138
const std::vector<LaneChangePhaseMetrics> & prepare_metrics,
139-
const lane_change::TargetObjects & target_objects, LaneChangePaths & candidate_paths) const;
139+
const lane_change::TargetObjects & target_objects,
140+
const std::vector<std::vector<int64_t>> & sorted_lane_ids,
141+
LaneChangePaths & candidate_paths) const;
142+
143+
bool get_path_using_path_shifter(
144+
const std::vector<LaneChangePhaseMetrics> & prepare_metrics,
145+
const lane_change::TargetObjects & target_objects,
146+
const std::vector<std::vector<int64_t>> & sorted_lane_ids,
147+
LaneChangePaths & candidate_paths) const;
140148

141149
bool check_candidate_path_safety(
142150
const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const;

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,8 @@ std::vector<lane_change::TrajectoryGroup> generate_frenet_candidates(
105105
const std::vector<LaneChangePhaseMetrics> & metrics);
106106

107107
std::optional<LaneChangePath> get_candidate_path(
108-
const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr);
108+
const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr,
109+
const std::vector<std::vector<int64_t>> & sorted_lane_ids);
109110
} // namespace autoware::behavior_path_planner::utils::lane_change
110111

111112
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_

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

+3-2
Original file line numberDiff line numberDiff line change
@@ -73,8 +73,9 @@ void set_prepare_velocity(
7373
PathWithLaneId & prepare_segment, const double current_velocity, const double prepare_velocity);
7474

7575
std::vector<int64_t> replaceWithSortedIds(
76-
const std::vector<int64_t> & original_lane_ids,
77-
const std::vector<std::vector<int64_t>> & sorted_lane_ids);
76+
const std::vector<int64_t> & current_lane_ids,
77+
const std::vector<std::vector<int64_t>> & sorted_lane_ids, std::vector<int64_t> & prev_lane_ids,
78+
std::vector<int64_t> & prev_sorted_lane_ids);
7879

7980
std::vector<std::vector<int64_t>> get_sorted_lane_ids(const CommonDataPtr & common_data_ptr);
8081

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+66-52
Original file line numberDiff line numberDiff line change
@@ -1092,20 +1092,81 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths)
10921092
}
10931093

10941094
const auto & current_lanes = get_current_lanes();
1095-
const auto & target_lanes = get_target_lanes();
10961095

1097-
const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_);
10981096
const auto target_objects = get_target_objects(filtered_objects_, current_lanes);
10991097

11001098
const auto prepare_phase_metrics = get_prepare_metrics();
11011099

1100+
const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_);
11021101
if (
11031102
common_data_ptr_->lc_param_ptr->frenet.enable &&
11041103
common_data_ptr_->transient_data.is_ego_near_current_terminal_start) {
1105-
return get_path_using_frenet(prepare_phase_metrics, target_objects, candidate_paths);
1104+
return get_path_using_frenet(
1105+
prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths);
1106+
}
1107+
1108+
return get_path_using_path_shifter(
1109+
prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths);
1110+
}
1111+
1112+
bool NormalLaneChange::get_path_using_frenet(
1113+
const std::vector<LaneChangePhaseMetrics> & prepare_metrics,
1114+
const lane_change::TargetObjects & target_objects,
1115+
const std::vector<std::vector<int64_t>> & sorted_lane_ids,
1116+
LaneChangePaths & candidate_paths) const
1117+
{
1118+
stop_watch_.tic("frenet_candidates");
1119+
constexpr auto found_safe_path = true;
1120+
const auto frenet_candidates = utils::lane_change::generate_frenet_candidates(
1121+
common_data_ptr_, prev_module_output_.path, prepare_metrics);
1122+
RCLCPP_DEBUG(
1123+
logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(),
1124+
stop_watch_.toc("frenet_candidates"));
1125+
1126+
for (const auto & frenet_candidate : frenet_candidates) {
1127+
std::optional<LaneChangePath> candidate_path_opt;
1128+
try {
1129+
candidate_path_opt =
1130+
utils::lane_change::get_candidate_path(frenet_candidate, common_data_ptr_, sorted_lane_ids);
1131+
} catch (const std::exception & e) {
1132+
RCLCPP_DEBUG(logger_, "%s", e.what());
1133+
}
1134+
1135+
if (!candidate_path_opt) {
1136+
continue;
1137+
}
1138+
try {
1139+
if (check_candidate_path_safety(*candidate_path_opt, target_objects)) {
1140+
RCLCPP_DEBUG(
1141+
logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]",
1142+
frenet_candidates.size(), stop_watch_.toc("frenet_candidates"));
1143+
candidate_paths.push_back(*candidate_path_opt);
1144+
return found_safe_path;
1145+
}
1146+
} catch (const std::exception & e) {
1147+
RCLCPP_DEBUG(logger_, "%s", e.what());
1148+
}
1149+
1150+
if (candidate_paths.empty()) {
1151+
candidate_paths.push_back(*candidate_path_opt);
1152+
}
11061153
}
1154+
1155+
RCLCPP_DEBUG(
1156+
logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(),
1157+
stop_watch_.toc("frenet_candidates"));
1158+
return !found_safe_path;
1159+
}
1160+
1161+
bool NormalLaneChange::get_path_using_path_shifter(
1162+
const std::vector<LaneChangePhaseMetrics> & prepare_metrics,
1163+
const lane_change::TargetObjects & target_objects,
1164+
const std::vector<std::vector<int64_t>> & sorted_lane_ids,
1165+
LaneChangePaths & candidate_paths) const
1166+
{
1167+
const auto & target_lanes = get_target_lanes();
11071168
candidate_paths.reserve(
1108-
prepare_phase_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num);
1169+
prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num);
11091170

11101171
const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time;
11111172
const auto dist_to_next_regulatory_element =
@@ -1124,7 +1185,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths)
11241185
return lc_diff > lane_change_parameters_->trajectory.th_lane_changing_length_diff;
11251186
};
11261187

1127-
for (const auto & prep_metric : prepare_phase_metrics) {
1188+
for (const auto & prep_metric : prepare_metrics) {
11281189
const auto debug_print = [&](const std::string & s) {
11291190
RCLCPP_DEBUG(
11301191
logger_, "%s | prep_time: %.5f | lon_acc: %.5f | prep_len: %.5f", s.c_str(),
@@ -1199,53 +1260,6 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths)
11991260
return false;
12001261
}
12011262

1202-
bool NormalLaneChange::get_path_using_frenet(
1203-
const std::vector<LaneChangePhaseMetrics> & prepare_metrics,
1204-
const lane_change::TargetObjects & target_objects, LaneChangePaths & candidate_paths) const
1205-
{
1206-
stop_watch_.tic("frenet_candidates");
1207-
constexpr auto found_safe_path = true;
1208-
const auto frenet_candidates = utils::lane_change::generate_frenet_candidates(
1209-
common_data_ptr_, prev_module_output_.path, prepare_metrics);
1210-
RCLCPP_DEBUG(
1211-
logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(),
1212-
stop_watch_.toc("frenet_candidates"));
1213-
1214-
for (const auto & frenet_candidate : frenet_candidates) {
1215-
std::optional<LaneChangePath> candidate_path_opt;
1216-
try {
1217-
candidate_path_opt =
1218-
utils::lane_change::get_candidate_path(frenet_candidate, common_data_ptr_);
1219-
} catch (const std::exception & e) {
1220-
RCLCPP_DEBUG(logger_, "%s", e.what());
1221-
}
1222-
1223-
if (!candidate_path_opt) {
1224-
continue;
1225-
}
1226-
try {
1227-
if (check_candidate_path_safety(*candidate_path_opt, target_objects)) {
1228-
RCLCPP_DEBUG(
1229-
logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]",
1230-
frenet_candidates.size(), stop_watch_.toc("frenet_candidates"));
1231-
candidate_paths.push_back(*candidate_path_opt);
1232-
return found_safe_path;
1233-
}
1234-
} catch (const std::exception & e) {
1235-
RCLCPP_DEBUG(logger_, "%s", e.what());
1236-
}
1237-
1238-
if (candidate_paths.empty()) {
1239-
candidate_paths.push_back(*candidate_path_opt);
1240-
}
1241-
}
1242-
1243-
RCLCPP_DEBUG(
1244-
logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(),
1245-
stop_watch_.toc("frenet_candidates"));
1246-
return !found_safe_path;
1247-
}
1248-
12491263
bool NormalLaneChange::check_candidate_path_safety(
12501264
const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const
12511265
{

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp

+30-21
Original file line numberDiff line numberDiff line change
@@ -366,10 +366,14 @@ LaneChangePath construct_candidate_path(
366366
throw std::logic_error("Lane change end idx not found on target path.");
367367
}
368368

369+
std::vector<int64_t> prev_ids;
370+
std::vector<int64_t> prev_sorted_ids;
369371
for (size_t i = 0; i < shifted_path.path.points.size(); ++i) {
370372
auto & point = shifted_path.path.points.at(i);
371373
if (i < *lc_end_idx_opt) {
372-
point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids);
374+
const auto & current_ids = point.lane_ids;
375+
point.lane_ids =
376+
replaceWithSortedIds(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids);
373377
point.point.longitudinal_velocity_mps = std::min(
374378
point.point.longitudinal_velocity_mps, static_cast<float>(terminal_lane_changing_velocity));
375379
continue;
@@ -501,40 +505,48 @@ std::vector<lane_change::TrajectoryGroup> generate_frenet_candidates(
501505
}
502506

503507
std::optional<LaneChangePath> get_candidate_path(
504-
const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr)
508+
const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr,
509+
const std::vector<std::vector<int64_t>> & sorted_lane_ids)
505510
{
506511
if (trajectory_group.lane_changing.frenet_points.empty()) {
507512
return std::nullopt;
508513
}
509514

510515
ShiftedPath shifted_path;
511-
PathPointWithLaneId pp;
516+
std::vector<int64_t> prev_ids;
517+
std::vector<int64_t> prev_sorted_ids;
512518
const auto & lane_changing_candidate = trajectory_group.lane_changing;
513519
const auto & target_lane_ref_path = trajectory_group.target_lane_ref_path;
514520
const auto & prepare_segment = trajectory_group.prepare;
515521
const auto & prepare_metric = trajectory_group.prepare_metric;
516522
const auto & initial_state = trajectory_group.initial_state;
517523
const auto & target_ref_sums = trajectory_group.target_lane_ref_path_dist;
518-
for (auto i = 0UL; i < lane_changing_candidate.poses.size(); ++i) {
519-
const auto s = lane_changing_candidate.frenet_points[i].s;
520-
pp.point.pose = lane_changing_candidate.poses[i];
521-
pp.point.longitudinal_velocity_mps =
522-
static_cast<float>(lane_changing_candidate.longitudinal_velocities[i]);
523-
pp.point.lateral_velocity_mps =
524-
static_cast<float>(lane_changing_candidate.lateral_velocities[i]);
525-
pp.point.heading_rate_rps = static_cast<float>(
526-
lane_changing_candidate
527-
.curvatures[i]); // TODO(Maxime): dirty way to attach the curvature at each point
528-
// copy from original reference path
524+
auto zipped_candidates = ranges::views::zip(
525+
lane_changing_candidate.poses, lane_changing_candidate.frenet_points,
526+
lane_changing_candidate.longitudinal_velocities, lane_changing_candidate.lateral_velocities,
527+
lane_changing_candidate.curvatures);
528+
529+
for (const auto & [pose, frenet_point, longitudinal_velocity, lateral_velocity, curvature] :
530+
zipped_candidates) {
531+
// Find the reference index
532+
const auto & s = frenet_point.s;
529533
auto ref_i_itr = std::find_if(
530534
target_ref_sums.begin(), target_ref_sums.end(),
531535
[s](const double ref_s) { return ref_s > s; });
532536
auto ref_i = std::distance(target_ref_sums.begin(), ref_i_itr);
533-
pp.point.pose.position.z = target_lane_ref_path.points[ref_i].point.pose.position.z;
534-
pp.lane_ids = target_lane_ref_path.points[ref_i].lane_ids;
535537

536-
shifted_path.shift_length.push_back(lane_changing_candidate.frenet_points[i].d);
537-
shifted_path.path.points.push_back(pp);
538+
PathPointWithLaneId point;
539+
point.point.pose = pose;
540+
point.point.longitudinal_velocity_mps = static_cast<float>(longitudinal_velocity);
541+
point.point.lateral_velocity_mps = static_cast<float>(lateral_velocity);
542+
point.point.heading_rate_rps = static_cast<float>(curvature);
543+
point.point.pose.position.z = target_lane_ref_path.points[ref_i].point.pose.position.z;
544+
const auto & current_ids = target_lane_ref_path.points[ref_i].lane_ids;
545+
point.lane_ids = replaceWithSortedIds(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids);
546+
547+
// Add to shifted path
548+
shifted_path.shift_length.push_back(frenet_point.d);
549+
shifted_path.path.points.push_back(point);
538550
}
539551

540552
if (shifted_path.path.points.empty()) {
@@ -581,16 +593,13 @@ std::optional<LaneChangePath> get_candidate_path(
581593
ShiftLine sl;
582594

583595
sl.start = lane_changing_candidate.poses.front();
584-
// prepare_segment.points.back() .point.pose; // TODO(Maxime): should it be 1st point of
585-
// lane_changing_candidate ?
586596
sl.end = lane_changing_candidate.poses.back();
587597
sl.start_shift_length = 0.0;
588598
sl.end_shift_length = initial_state.position.d;
589599
sl.start_idx = 0UL;
590600
sl.end_idx = shifted_path.shift_length.size() - 1;
591601

592602
info.shift_line = sl;
593-
594603
info.terminal_lane_changing_velocity = lane_changing_candidate.longitudinal_velocities.back();
595604
info.lateral_acceleration = lane_changing_candidate.lateral_accelerations.front();
596605

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

+13-5
Original file line numberDiff line numberDiff line change
@@ -455,17 +455,25 @@ std::vector<std::vector<int64_t>> get_sorted_lane_ids(const CommonDataPtr & comm
455455
}
456456

457457
std::vector<int64_t> replaceWithSortedIds(
458-
const std::vector<int64_t> & original_lane_ids,
459-
const std::vector<std::vector<int64_t>> & sorted_lane_ids)
458+
const std::vector<int64_t> & current_lane_ids,
459+
const std::vector<std::vector<int64_t>> & sorted_lane_ids, std::vector<int64_t> & prev_lane_ids,
460+
std::vector<int64_t> & prev_sorted_lane_ids)
460461
{
461-
for (const auto original_id : original_lane_ids) {
462+
if (current_lane_ids == prev_lane_ids) {
463+
return prev_sorted_lane_ids;
464+
}
465+
466+
for (const auto original_id : current_lane_ids) {
462467
for (const auto & sorted_id : sorted_lane_ids) {
463468
if (std::find(sorted_id.cbegin(), sorted_id.cend(), original_id) != sorted_id.cend()) {
464-
return sorted_id;
469+
prev_lane_ids = current_lane_ids;
470+
prev_sorted_lane_ids = sorted_id;
471+
return prev_sorted_lane_ids;
465472
}
466473
}
467474
}
468-
return original_lane_ids;
475+
476+
return current_lane_ids;
469477
}
470478

471479
CandidateOutput assignToCandidate(

0 commit comments

Comments
 (0)