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(obstacle_avoidance_planner): fix drivable area polygon point order direction #2691

Merged
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
16 changes: 8 additions & 8 deletions planning/obstacle_avoidance_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -661,18 +661,18 @@ bg_polygon createDrivablePolygon(
{
bg_polygon drivable_area_poly;

// right bound
for (const auto rp : right_bound) {
drivable_area_poly.outer().push_back(bg_point(rp.x, rp.y));
}

// left bound
auto reversed_left_bound = left_bound;
std::reverse(reversed_left_bound.begin(), reversed_left_bound.end());
for (const auto lp : reversed_left_bound) {
for (const auto lp : left_bound) {
drivable_area_poly.outer().push_back(bg_point(lp.x, lp.y));
}

// right bound
auto reversed_right_bound = right_bound;
std::reverse(reversed_right_bound.begin(), reversed_right_bound.end());
for (const auto rp : reversed_right_bound) {
drivable_area_poly.outer().push_back(bg_point(rp.x, rp.y));
}

drivable_area_poly.outer().push_back(drivable_area_poly.outer().front());
return drivable_area_poly;
}
Expand Down