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_path_planner): pull over no stopping area #2492

Merged
merged 2 commits into from
Dec 22, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -27,6 +27,7 @@ namespace behavior_path_planner
{
using autoware_auto_planning_msgs::msg::PathPointWithLaneId;
using tier4_autoware_utils::LinearRing2d;
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;

class GoalSearcher : public GoalSearcherBase
{
Expand All @@ -42,6 +43,8 @@ class GoalSearcher : public GoalSearcherBase
bool checkCollision(const Pose & pose) const;
bool checkCollisionWithLongitudinalDistance(
const Pose & ego_pose, const PredictedObjects & dynamic_objects) const;
BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const;
bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const;

LinearRing2d vehicle_footprint_{};
std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map_{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
namespace behavior_path_planner
{
using lane_departure_checker::LaneDepartureChecker;
using lanelet::autoware::NoStoppingArea;
using tier4_autoware_utils::calcOffsetPose;
using tier4_autoware_utils::inverseTransformPose;

Expand Down Expand Up @@ -86,9 +87,15 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose)

const auto transformed_vehicle_footprint =
transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(search_pose));

if (isInAreas(transformed_vehicle_footprint, getNoStoppingAreaPolygons(pull_over_lanes))) {
continue;
}

if (LaneDepartureChecker::isOutOfLane(lanes, transformed_vehicle_footprint)) {
continue;
}

if (checkCollision(search_pose)) {
continue;
}
Expand Down Expand Up @@ -241,4 +248,29 @@ void GoalSearcher::createAreaPolygons(std::vector<Pose> original_search_poses)
}
}

BasicPolygons2d GoalSearcher::getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const
{
// std::vector<lanelet::BasicPolygon2d> polys{}
kosuke55 marked this conversation as resolved.
Show resolved Hide resolved
BasicPolygons2d area_polygons{};
for (const auto & ll : lanes) {
for (const auto & reg_elem : ll.regulatoryElementsAs<NoStoppingArea>()) {
for (const auto & area : reg_elem->noStoppingAreas()) {
const auto & area_poly = lanelet::utils::to2D(area).basicPolygon();
area_polygons.push_back(area_poly);
}
}
}
return area_polygons;
}

bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const
{
for (const auto & area : areas) {
if (boost::geometry::intersects(area, footprint)) {
return true;
}
}
return false;
}

} // namespace behavior_path_planner