Skip to content

Commit 132d7d8

Browse files
authored
feat(lane_change): wait approval with abort state (#6234)
Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
1 parent 82d1b10 commit 132d7d8

File tree

2 files changed

+44
-28
lines changed

2 files changed

+44
-28
lines changed

planning/behavior_path_lane_change_module/src/interface.cpp

+11-2
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ bool LaneChangeInterface::isExecutionRequested() const
7070

7171
bool LaneChangeInterface::isExecutionReady() const
7272
{
73-
return module_type_->isSafe();
73+
return module_type_->isSafe() && !module_type_->isAbortState();
7474
}
7575

7676
void LaneChangeInterface::updateData()
@@ -116,7 +116,16 @@ BehaviorModuleOutput LaneChangeInterface::plan()
116116
}
117117

118118
updateSteeringFactorPtr(output);
119-
clearWaitingApproval();
119+
if (module_type_->isAbortState()) {
120+
waitApproval();
121+
removeRTCStatus();
122+
const auto candidate = planCandidate();
123+
path_candidate_ = std::make_shared<PathWithLaneId>(candidate.path_candidate);
124+
updateRTCStatus(
125+
candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change);
126+
} else {
127+
clearWaitingApproval();
128+
}
120129

121130
return output;
122131
}

planning/behavior_path_lane_change_module/src/scene.cpp

+33-26
Original file line numberDiff line numberDiff line change
@@ -144,6 +144,19 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
144144
{
145145
BehaviorModuleOutput output;
146146

147+
if (isAbortState() && abort_path_) {
148+
output.path = abort_path_->path;
149+
output.reference_path = prev_module_reference_path_;
150+
output.turn_signal_info = prev_turn_signal_info_;
151+
extendOutputDrivableArea(output);
152+
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
153+
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
154+
output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
155+
planner_data_->parameters.ego_nearest_dist_threshold,
156+
planner_data_->parameters.ego_nearest_yaw_threshold);
157+
return output;
158+
}
159+
147160
const auto current_lanes = getCurrentLanes();
148161
if (current_lanes.empty()) {
149162
RCLCPP_WARN(logger_, "Current lanes not found!!! Something wrong.");
@@ -157,7 +170,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
157170
const auto terminal_path =
158171
calcTerminalLaneChangePath(current_lanes, getLaneChangeLanes(current_lanes, direction_));
159172
if (!terminal_path) {
160-
RCLCPP_WARN(logger_, "Terminal path not found!!!");
173+
RCLCPP_DEBUG(logger_, "Terminal path not found!!!");
161174
output.path = prev_module_path_;
162175
output.reference_path = prev_module_reference_path_;
163176
output.drivable_area_info = prev_drivable_area_info_;
@@ -1525,7 +1538,7 @@ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(
15251538
-(lane_change_buffer + next_lane_change_buffer + distance_to_terminal_from_goal));
15261539

15271540
if (!lane_changing_start_pose) {
1528-
RCLCPP_WARN(logger_, "Reject: lane changing start pose not found!!!");
1541+
RCLCPP_DEBUG(logger_, "Reject: lane changing start pose not found!!!");
15291542
return {};
15301543
}
15311544

@@ -1534,7 +1547,7 @@ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(
15341547

15351548
// Check if the lane changing start point is not on the lanes next to target lanes,
15361549
if (target_length_from_lane_change_start_pose > 0.0) {
1537-
RCLCPP_WARN(logger_, "lane change start getEgoPose() is behind target lanelet!");
1550+
RCLCPP_DEBUG(logger_, "lane change start getEgoPose() is behind target lanelet!");
15381551
return {};
15391552
}
15401553

@@ -1552,7 +1565,7 @@ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(
15521565
minimum_lane_changing_velocity, next_lane_change_buffer);
15531566

15541567
if (target_segment.points.empty()) {
1555-
RCLCPP_WARN(logger_, "Reject: target segment is empty!! something wrong...");
1568+
RCLCPP_DEBUG(logger_, "Reject: target segment is empty!! something wrong...");
15561569
return {};
15571570
}
15581571

@@ -1581,7 +1594,7 @@ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(
15811594
lane_change_info.terminal_lane_changing_velocity = minimum_lane_changing_velocity;
15821595

15831596
if (!is_valid_start_point) {
1584-
RCLCPP_WARN(
1597+
RCLCPP_DEBUG(
15851598
logger_,
15861599
"Reject: lane changing points are not inside of the target preferred lanes or its "
15871600
"neighbors");
@@ -1596,7 +1609,7 @@ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(
15961609
next_lane_change_buffer);
15971610

15981611
if (target_lane_reference_path.points.empty()) {
1599-
RCLCPP_WARN(logger_, "Reject: target_lane_reference_path is empty!!");
1612+
RCLCPP_DEBUG(logger_, "Reject: target_lane_reference_path is empty!!");
16001613
return {};
16011614
}
16021615

@@ -1855,31 +1868,25 @@ bool NormalLaneChange::calcAbortPath()
18551868

18561869
ShiftedPath shifted_path;
18571870
// offset front side
1858-
// bool offset_back = false;
18591871
if (!path_shifter.generate(&shifted_path)) {
18601872
RCLCPP_ERROR(logger_, "failed to generate abort shifted path.");
18611873
}
18621874

1863-
const auto arc_position = lanelet::utils::getArcCoordinates(
1864-
reference_lanelets, shifted_path.path.points.at(abort_return_idx).point.pose);
1865-
const PathWithLaneId reference_lane_segment = std::invoke([&]() {
1866-
const double s_start = arc_position.length;
1867-
double s_end = std::max(lanelet::utils::getLaneletLength2d(reference_lanelets), s_start);
1868-
1869-
if (
1870-
!reference_lanelets.empty() &&
1871-
route_handler->isInGoalRouteSection(reference_lanelets.back())) {
1872-
const auto goal_arc_coordinates =
1873-
lanelet::utils::getArcCoordinates(reference_lanelets, route_handler->getGoalPose());
1874-
const double forward_length = std::max(goal_arc_coordinates.length, s_start);
1875-
s_end = std::min(s_end, forward_length);
1875+
PathWithLaneId reference_lane_segment = prev_module_path_;
1876+
{
1877+
const auto terminal_path =
1878+
calcTerminalLaneChangePath(reference_lanelets, selected_path.info.target_lanes);
1879+
if (terminal_path) {
1880+
reference_lane_segment = terminal_path->path;
18761881
}
1877-
PathWithLaneId ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end, true);
1878-
ref.points.back().point.longitudinal_velocity_mps = std::min(
1879-
ref.points.back().point.longitudinal_velocity_mps,
1880-
static_cast<float>(lane_change_parameters_->minimum_lane_changing_velocity));
1881-
return ref;
1882-
});
1882+
const auto return_pose = shifted_path.path.points.at(abort_return_idx).point.pose;
1883+
const auto seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
1884+
reference_lane_segment.points, return_pose, common_param.ego_nearest_dist_threshold,
1885+
common_param.ego_nearest_yaw_threshold);
1886+
reference_lane_segment.points = motion_utils::cropPoints(
1887+
reference_lane_segment.points, return_pose.position, seg_idx,
1888+
common_param.forward_path_length, 0.0);
1889+
}
18831890

18841891
auto abort_path = selected_path;
18851892
abort_path.shifted_path = shifted_path;

0 commit comments

Comments
 (0)