Skip to content

Commit

Permalink
feat(behavior_path_planner): add virtual stop wall for lane change (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#4808)

Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
  • Loading branch information
rej55 committed Sep 27, 2023
1 parent c6fc9e2 commit 734f25b
Show file tree
Hide file tree
Showing 4 changed files with 21 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,10 @@ class LaneChangeBase
return direction_;
}

boost::optional<Pose> getStopPose() const { return lane_change_stop_pose_; }

void resetStopPose() { lane_change_stop_pose_ = boost::none; }

protected:
virtual lanelet::ConstLanelets getCurrentLanes() const = 0;

Expand Down Expand Up @@ -244,6 +248,7 @@ class LaneChangeBase
PathWithLaneId prev_module_path_{};
DrivableAreaInfo prev_drivable_area_info_{};
TurnSignalInfo prev_turn_signal_info_{};
boost::optional<Pose> lane_change_stop_pose_{boost::none};

PathWithLaneId prev_approved_path_{};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,8 @@ class NormalLaneChange : public LaneChangeBase
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
const lanelet::ConstLanelets & target_backward_lanes) const;

void setStopPose(const Pose & stop_pose);

rclcpp::Logger logger_ = rclcpp::get_logger("lane_change").get_child(getModuleTypeStr());
};
} // namespace behavior_path_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,7 @@ void LaneChangeInterface::updateData()
module_type_->setPreviousModulePaths(
getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path);
module_type_->updateSpecialData();
module_type_->resetStopPose();
}

BehaviorModuleOutput LaneChangeInterface::plan()
Expand All @@ -221,6 +222,8 @@ BehaviorModuleOutput LaneChangeInterface::plan()
*prev_approved_path_ = *getPreviousModuleOutput().path;
module_type_->insertStopPoint(module_type_->getLaneChangeStatus().target_lanes, *output.path);

stop_pose_ = module_type_->getStopPose();

updateSteeringFactorPtr(output);
clearWaitingApproval();

Expand Down Expand Up @@ -249,6 +252,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()

path_reference_ = getPreviousModuleOutput().reference_path;

stop_pose_ = module_type_->getStopPose();

if (!module_type_->isValidPath()) {
removeRTCStatus();
path_candidate_ = std::make_shared<PathWithLaneId>();
Expand Down Expand Up @@ -286,6 +291,7 @@ void LaneChangeInterface::updateModuleParams(const std::any & parameters)

void LaneChangeInterface::setData(const std::shared_ptr<const PlannerData> & data)
{
planner_data_ = data;
module_type_->setData(data);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()
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);
setStopPose(stop_point.point.pose);
}

const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points);
Expand Down Expand Up @@ -198,6 +199,7 @@ void NormalLaneChange::insertStopPoint(
const double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer;
if (stopping_distance > 0.0) {
const auto stop_point = utils::insertStopPoint(stopping_distance, path);
setStopPose(stop_point.point.pose);
}
}

Expand Down Expand Up @@ -1455,4 +1457,10 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(

return path_safety_status;
}

void NormalLaneChange::setStopPose(const Pose & stop_pose)
{
lane_change_stop_pose_ = stop_pose;
}

} // namespace behavior_path_planner

0 comments on commit 734f25b

Please sign in to comment.