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

refactor(crosswalk): clean up the structure and create a brief flowchart #7868

Merged
merged 4 commits into from
Jul 18, 2024
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 @@ -8,6 +8,41 @@ This module judges whether the ego should stop in front of the crosswalk in orde
![crosswalk_module](docs/crosswalk_module.svg){width=1100}
</figure>

## Flowchart

```plantuml
@startuml
skinparam monochrome true
title modifyPathVelocity
start
:getPathEndPointsOnCrosswalk;
group apply slow down
:applySlowDownByLanleet2Map;
:applySlowDownByOcclusion;
end group
group calculate stop pose
:getDefaultStopPose;
:resamplePath;
:checkStopForCrosswalkUsers;
:checkStopForStuckVehicles;
end group
group apply stop
:getNearestStopFactor;
:setSafe;
:setDistanceToStop;
if (isActivated() is True?) then (yes)
:planGo;
else (no)
:planStop;
endif
end group
stop
@enduml
```

## Features

### Yield the Way to the Pedestrians
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,13 +97,14 @@ std::set<int64_t> getCrosswalkIdSetOnPath(

bool checkRegulatoryElementExistence(const lanelet::LaneletMapPtr & lanelet_map_ptr);

std::vector<geometry_msgs::msg::Point> getPolygonIntersects(
std::optional<std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
getPathEndPointsOnCrosswalk(
const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon,
const geometry_msgs::msg::Point & ego_pos, const size_t max_num);
const geometry_msgs::msg::Point & ego_pos);

std::vector<geometry_msgs::msg::Point> getLinestringIntersects(
const PathWithLaneId & ego_path, const lanelet::BasicLineString2d & linestring,
const geometry_msgs::msg::Point & ego_pos, const size_t max_num);
const geometry_msgs::msg::Point & ego_pos);

std::optional<lanelet::ConstLineString3d> getStopLineFromMap(
const lanelet::Id lane_id, const lanelet::LaneletMapPtr & lanelet_map_ptr,
Expand Down
Loading
Loading