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

feat(behavior_velocity_planner): improve pull over and pull out module #251

Merged
merged 2 commits into from
Jan 19, 2023
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
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class PullOutModule : public SceneModuleInterface
const std::vector<Pose> & start_pose_candidates, const Pose & goal_pose);
void planWithPriorityOnShortBackDistance(
const std::vector<Pose> & start_pose_candidates, const Pose & goal_pose);
void generateStopPath();
PathWithLaneId generateStopPath() const;
void updatePullOutStatus();
static bool isOverlappedWithLane(
const lanelet::ConstLanelet & candidate_lanelet,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,9 @@ BehaviorModuleOutput PullOutModule::plan()
if (!status_.is_safe) {
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path");
const PathWithLaneId stop_path = generateStopPath();
output.path = std::make_shared<PathWithLaneId>(stop_path);
path_candidate_ = std::make_shared<PathWithLaneId>(stop_path);
return output;
}

Expand Down Expand Up @@ -430,11 +433,11 @@ void PullOutModule::planWithPriorityOnShortBackDistance(
}
}

void PullOutModule::generateStopPath()
PathWithLaneId PullOutModule::generateStopPath() const
{
const auto & current_pose = planner_data_->self_pose->pose;
constexpr double dummy_path_distance = 1.0;
const auto & moved_pose = calcOffsetPose(current_pose, dummy_path_distance, 0, 0);
const auto moved_pose = calcOffsetPose(current_pose, dummy_path_distance, 0, 0);

// convert Pose to PathPointWithLaneId with 0 velocity.
auto toPathPointWithLaneId = [this](const Pose & pose) {
Expand All @@ -452,9 +455,15 @@ void PullOutModule::generateStopPath()
path.points.push_back(toPathPointWithLaneId(current_pose));
path.points.push_back(toPathPointWithLaneId(moved_pose));

status_.pull_out_path.partial_paths.push_back(path);
status_.pull_out_path.start_pose = current_pose;
status_.pull_out_path.end_pose = current_pose;
// generate drivable area
const auto shorten_lanes = util::cutOverlappedLanes(path, status_.lanes);
const auto expanded_lanes = util::expandLanelets(
shorten_lanes, parameters_.drivable_area_left_bound_offset,
parameters_.drivable_area_right_bound_offset);
util::generateDrivableArea(
path, expanded_lanes, planner_data_->parameters.vehicle_length, planner_data_);

return path;
}

void PullOutModule::updatePullOutStatus()
Expand Down Expand Up @@ -498,7 +507,9 @@ void PullOutModule::updatePullOutStatus()
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000, "Not found safe pull out path, generate stop path");
status_.back_finished = true; // no need to drive backward
generateStopPath();
status_.pull_out_path.partial_paths.push_back(generateStopPath());
status_.pull_out_path.start_pose = current_pose;
status_.pull_out_path.end_pose = current_pose;
}

checkBackFinished();
Expand Down Expand Up @@ -546,8 +557,10 @@ std::vector<Pose> PullOutModule::searchBackedPoses()
// check the back pose is near the lane end
const double length_to_backed_pose =
lanelet::utils::getArcCoordinates(status_.pull_out_lanes, *backed_pose).length;
const double length_to_lane_end =
lanelet::utils::getLaneletLength2d(status_.pull_out_lanes.back());
double length_to_lane_end = 0.0;
for (const auto & lane : status_.pull_out_lanes) {
length_to_lane_end += lanelet::utils::getLaneletLength2d(lane);
}
const double distance_from_lane_end = length_to_lane_end - length_to_backed_pose;
if (distance_from_lane_end < parameters_.ignore_distance_from_lane_end) {
RCLCPP_WARN_THROTTLE(
Expand Down