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

fix(avoidance): unintentional path cut #5887

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 14 additions & 14 deletions planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@

// lanelet info
data.current_lanelets = utils::avoidance::getCurrentLanesFromPath(
*getPreviousModuleOutput().reference_path, planner_data_);
getPreviousModuleOutput().reference_path, planner_data_);

data.extend_lanelets =
utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_);
Expand All @@ -233,8 +233,8 @@
});

// calc drivable bound
const auto shorten_lanes =
utils::cutOverlappedLanes(*getPreviousModuleOutput().path, data.drivable_lanes);
auto tmp_path = getPreviousModuleOutput().path;
const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes);
data.left_bound = toLineString3d(utils::calcBound(
planner_data_->route_handler, shorten_lanes, parameters_->use_hatched_road_markings,
parameters_->use_intersection_areas, true));
Expand All @@ -244,9 +244,9 @@

// reference path
if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path);
data.reference_path_rough = extendBackwardLength(getPreviousModuleOutput().path);
} else {
data.reference_path_rough = *getPreviousModuleOutput().path;
data.reference_path_rough = getPreviousModuleOutput().path;

Check warning on line 249 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L249

Added line #L249 was not covered by tests
RCLCPP_WARN(getLogger(), "Previous module lane is updated. Don't use latest reference path.");
}

Expand Down Expand Up @@ -910,17 +910,17 @@
}

if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
output.path = std::make_shared<PathWithLaneId>(spline_shift_path.path);
output.path = spline_shift_path.path;
} else {
output.path = getPreviousModuleOutput().path;
RCLCPP_WARN(getLogger(), "Previous module lane is updated. Do nothing.");
}

output.reference_path = getPreviousModuleOutput().reference_path;
path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);

const size_t ego_idx = planner_data_->findEgoIndex(output.path->points);
utils::clipPathLength(*output.path, ego_idx, planner_data_->parameters);
const size_t ego_idx = planner_data_->findEgoIndex(output.path.points);
utils::clipPathLength(output.path, ego_idx, planner_data_->parameters);

// Drivable area generation.
{
Expand Down Expand Up @@ -995,7 +995,7 @@
}

path_candidate_ = std::make_shared<PathWithLaneId>(planCandidate().path_candidate);
path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);

Check warning on line 998 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/src/scene.cpp#L998

Added line #L998 was not covered by tests

return out;
}
Expand Down Expand Up @@ -1169,11 +1169,11 @@
helper_->setData(planner_data_);

if (!helper_->isInitialized()) {
helper_->setPreviousSplineShiftPath(toShiftedPath(*getPreviousModuleOutput().path));
helper_->setPreviousLinearShiftPath(toShiftedPath(*getPreviousModuleOutput().path));
helper_->setPreviousReferencePath(*getPreviousModuleOutput().path);
helper_->setPreviousSplineShiftPath(toShiftedPath(getPreviousModuleOutput().path));
helper_->setPreviousLinearShiftPath(toShiftedPath(getPreviousModuleOutput().path));
helper_->setPreviousReferencePath(getPreviousModuleOutput().path);
helper_->setPreviousDrivingLanes(utils::avoidance::getCurrentLanesFromPath(
*getPreviousModuleOutput().reference_path, planner_data_));
getPreviousModuleOutput().reference_path, planner_data_));
}

debug_data_ = DebugData();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,8 @@
BehaviorModuleOutput output =
// use planner previous module reference path
getPreviousModuleOutput();
const PathWithLaneId smoothed_path =
modifyPathForSmoothGoalConnection(*(output.path), planner_data);
output.path = std::make_shared<PathWithLaneId>(smoothed_path);
const PathWithLaneId smoothed_path = modifyPathForSmoothGoalConnection(output.path, planner_data);
output.path = smoothed_path;

Check warning on line 37 in planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp#L36-L37

Added lines #L36 - L37 were not covered by tests
output.reference_path = getPreviousModuleOutput().reference_path;
return output;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1475 to 1474, 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 Down Expand Up @@ -282,7 +282,7 @@

resetPathCandidate();
resetPathReference();
path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);

Check warning on line 285 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L285

Added line #L285 was not covered by tests

updateOccupancyGrid();

Expand Down Expand Up @@ -761,7 +761,7 @@
// because it takes time for the trajectory to be reflected
auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath();
keepStoppedWithCurrentPath(current_path);
output.path = std::make_shared<PathWithLaneId>(current_path);
output.path = current_path;

Check warning on line 764 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L764

Added line #L764 was not covered by tests
}

setModifiedGoal(output);
Expand All @@ -777,14 +777,14 @@
{
if (prev_data_.found_path || !prev_data_.stop_path) {
// safe -> not_safe or no prev_stop_path: generate new stop_path
output.path = std::make_shared<PathWithLaneId>(generateStopPath());
output.path = generateStopPath();

Check warning on line 780 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L780

Added line #L780 was not covered by tests
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path");
} else {
// not_safe -> not_safe: use previous stop path
output.path = prev_data_.stop_path;
output.path = *prev_data_.stop_path;

Check warning on line 785 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L785

Added line #L785 was not covered by tests
// stop_pose_ is removed in manager every loop, so need to set every loop.
stop_pose_ = utils::getFirstStopPoseFromPath(*output.path);
stop_pose_ = utils::getFirstStopPoseFromPath(output.path);

Check warning on line 787 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L787

Added line #L787 was not covered by tests
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path");
}
Expand All @@ -800,20 +800,19 @@
current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop,
parameters_->maximum_jerk_for_stop);
if (stop_path) {
output.path = std::make_shared<PathWithLaneId>(*stop_path);
output.path = *stop_path;

Check warning on line 803 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L803

Added line #L803 was not covered by tests
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path");
} else {
output.path =
std::make_shared<PathWithLaneId>(thread_safe_data_.get_pull_over_path()->getCurrentPath());
output.path = thread_safe_data_.get_pull_over_path()->getCurrentPath();

Check warning on line 806 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L806

Added line #L806 was not covered by tests
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000,
"Collision detected, no feasible stop path found, cannot stop.");
}
} else {
// not_safe safe(no feasible stop path found) -> not_safe: use previous stop path
output.path = prev_data_.stop_path_after_approval;
output.path = *prev_data_.stop_path_after_approval;

Check warning on line 813 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L813

Added line #L813 was not covered by tests
// stop_pose_ is removed in manager every loop, so need to set every loop.
stop_pose_ = utils::getFirstStopPoseFromPath(*output.path);
stop_pose_ = utils::getFirstStopPoseFromPath(output.path);

Check warning on line 815 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L815

Added line #L815 was not covered by tests
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path");
}
}
Expand All @@ -826,7 +825,7 @@
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
} else {
const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
*output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters);
output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters);

Check warning on line 828 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L828

Added line #L828 was not covered by tests

DrivableAreaInfo current_drivable_area_info;
current_drivable_area_info.drivable_lanes = target_drivable_lanes;
Expand All @@ -853,9 +852,9 @@
{
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
const auto new_signal = calcTurnSignalInfo();
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);

Check warning on line 855 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L855

Added line #L855 was not covered by tests
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
*output.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
output.path, getEgoPose(), current_seg_idx, original_signal, new_signal,

Check warning on line 857 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L857

Added line #L857 was not covered by tests
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
}
Expand Down Expand Up @@ -942,11 +941,11 @@
BehaviorModuleOutput output{};
const BehaviorModuleOutput pull_over_output = planPullOverAsOutput();
output.modified_goal = pull_over_output.modified_goal;
output.path = std::make_shared<PathWithLaneId>(generateStopPath());
output.path = generateStopPath();

Check warning on line 944 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L944

Added line #L944 was not covered by tests
output.reference_path = getPreviousModuleOutput().reference_path;

const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
*output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters);
output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters);

Check warning on line 948 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L948

Added line #L948 was not covered by tests

DrivableAreaInfo current_drivable_area_info{};
current_drivable_area_info.drivable_lanes = target_drivable_lanes;
Expand Down Expand Up @@ -1054,7 +1053,7 @@
void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output)
{
if (prev_data_.found_path || !prev_data_.stop_path) {
prev_data_.stop_path = output.path;
prev_data_.stop_path = std::make_shared<PathWithLaneId>(output.path);

Check warning on line 1056 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1056

Added line #L1056 was not covered by tests
}

// for the next loop setOutput().
Expand Down Expand Up @@ -1086,7 +1085,7 @@
if (!isActivated() || (!is_safe && prev_data_.stop_path_after_approval)) {
return;
}
auto stop_path = std::make_shared<PathWithLaneId>(*output.path);
auto stop_path = std::make_shared<PathWithLaneId>(output.path);

Check warning on line 1088 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1088

Added line #L1088 was not covered by tests
for (auto & point : stop_path->points) {
point.point.longitudinal_velocity_mps = 0.0;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,14 +107,13 @@ class LaneChangeBase
virtual bool specialExpiredCheck() const { return false; }

virtual void setPreviousModulePaths(
const std::shared_ptr<PathWithLaneId> & prev_module_reference_path,
const std::shared_ptr<PathWithLaneId> & prev_module_path)
const PathWithLaneId & prev_module_reference_path, const PathWithLaneId & prev_module_path)
{
if (prev_module_reference_path) {
prev_module_reference_path_ = *prev_module_reference_path;
if (!prev_module_reference_path.points.empty()) {
prev_module_reference_path_ = prev_module_reference_path;
}
if (prev_module_path) {
prev_module_path_ = *prev_module_path;
if (!prev_module_path.points.empty()) {
prev_module_path_ = prev_module_path;
}
};

Expand Down
16 changes: 8 additions & 8 deletions planning/behavior_path_lane_change_module/src/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,8 +201,8 @@
module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info);
module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info);
auto output = module_type_->generateOutput();
path_reference_ = output.reference_path;
*prev_approved_path_ = *getPreviousModuleOutput().path;
path_reference_ = std::make_shared<PathWithLaneId>(output.reference_path);
*prev_approved_path_ = getPreviousModuleOutput().path;

Check warning on line 205 in planning/behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/interface.cpp#L205

Added line #L205 was not covered by tests

stop_pose_ = module_type_->getStopPose();

Expand All @@ -219,12 +219,12 @@

BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
{
*prev_approved_path_ = *getPreviousModuleOutput().path;
*prev_approved_path_ = getPreviousModuleOutput().path;

Check warning on line 222 in planning/behavior_path_lane_change_module/src/interface.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/interface.cpp#L222

Added line #L222 was not covered by tests
module_type_->insertStopPoint(
module_type_->getLaneChangeStatus().current_lanes, *prev_approved_path_);

BehaviorModuleOutput out;
out.path = std::make_shared<PathWithLaneId>(*prev_approved_path_);
out.path = *prev_approved_path_;
out.reference_path = getPreviousModuleOutput().reference_path;
out.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
out.drivable_area_info = getPreviousModuleOutput().drivable_area_info;
Expand All @@ -240,9 +240,9 @@
}

// change turn signal when the vehicle reaches at the end of the path for waiting lane change
out.turn_signal_info = getCurrentTurnSignalInfo(*out.path, out.turn_signal_info);
out.turn_signal_info = getCurrentTurnSignalInfo(out.path, out.turn_signal_info);

path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);

stop_pose_ = module_type_->getStopPose();

Expand Down Expand Up @@ -366,9 +366,9 @@
const auto current_position = module_type_->getEgoPosition();
const auto status = module_type_->getLaneChangeStatus();
const auto start_distance = motion_utils::calcSignedArcLength(
output.path->points, current_position, status.lane_change_path.info.shift_line.start.position);
output.path.points, current_position, status.lane_change_path.info.shift_line.start.position);
const auto finish_distance = motion_utils::calcSignedArcLength(
output.path->points, current_position, status.lane_change_path.info.shift_line.end.position);
output.path.points, current_position, status.lane_change_path.info.shift_line.end.position);

steering_factor_interface_ptr_->updateSteeringFactor(
{status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end},
Expand Down
24 changes: 12 additions & 12 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,38 +145,38 @@
BehaviorModuleOutput output;

if (isAbortState() && abort_path_) {
output.path = std::make_shared<PathWithLaneId>(abort_path_->path);
output.reference_path = std::make_shared<PathWithLaneId>(prev_module_reference_path_);
output.path = abort_path_->path;
output.reference_path = prev_module_reference_path_;
output.turn_signal_info = prev_turn_signal_info_;
insertStopPoint(status_.current_lanes, *output.path);
insertStopPoint(status_.current_lanes, output.path);
} else {
output.path = std::make_shared<PathWithLaneId>(getLaneChangePath().path);
output.path = getLaneChangePath().path;

const auto found_extended_path = extendPath();
if (found_extended_path) {
*output.path = utils::combinePath(*output.path, *found_extended_path);
output.path = utils::combinePath(output.path, *found_extended_path);
}
output.reference_path = std::make_shared<PathWithLaneId>(getReferencePath());
output.reference_path = getReferencePath();
output.turn_signal_info = updateOutputTurnSignal();

if (isStopState()) {
const auto current_velocity = getEgoVelocity();
const auto current_dist = calcSignedArcLength(
output.path->points, output.path->points.front().point.pose.position, getEgoPosition());
output.path.points, output.path.points.front().point.pose.position, getEgoPosition());
const auto stop_dist =
-(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc));
const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, *output.path);
const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, output.path);
setStopPose(stop_point.point.pose);
} else {
insertStopPoint(status_.target_lanes, *output.path);
insertStopPoint(status_.target_lanes, output.path);
}
}

extendOutputDrivableArea(output);

const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
*output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,

Check warning on line 179 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L179

Added line #L179 was not covered by tests
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);

Expand All @@ -189,7 +189,7 @@

const auto drivable_lanes = utils::lane_change::generateDrivableLanes(
*getRouteHandler(), status_.current_lanes, status_.target_lanes);
const auto shorten_lanes = utils::cutOverlappedLanes(*output.path, drivable_lanes);
const auto shorten_lanes = utils::cutOverlappedLanes(output.path, drivable_lanes);
const auto expanded_lanes = utils::expandLanelets(
shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
dp.drivable_area_types_to_skip);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -738,7 +738,8 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(
{
// TODO(Horibe) do some error handling when path is not available.

auto path = output.path ? output.path : planner_data->prev_output_path;
auto path = !output.path.points.empty() ? std::make_shared<PathWithLaneId>(output.path)
: planner_data->prev_output_path;
path->header = planner_data->route_handler->getRouteHeader();
path->header.stamp = this->now();

Expand Down
Loading
Loading