Skip to content

Commit

Permalink
feat(obstacle_avoidance_planner): add second check with boost::geomet…
Browse files Browse the repository at this point in the history
…ry::intersection

Signed-off-by: beyza <bnk@leodrive.ai>
  • Loading branch information
beyzanurkaya committed Jan 17, 2023
1 parent 11c0c8d commit 3c43118
Showing 1 changed file with 32 additions and 0 deletions.
32 changes: 32 additions & 0 deletions planning/obstacle_avoidance_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@ typedef bg::model::polygon<bg_point> bg_polygon;

namespace
{
namespace bg = boost::geometry;
using tier4_autoware_utils::LinearRing2d;
using tier4_autoware_utils::LineString2d;
std::vector<double> convertEulerAngleToMonotonic(const std::vector<double> & angle)
{
if (angle.empty()) {
Expand Down Expand Up @@ -708,6 +711,35 @@ bool isOutsideDrivableAreaFromRectangleFootprint(
tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, -base_to_left, 0.0)
.position;

LinearRing2d footprint_polygon;
LineString2d left_bound_line;
LineString2d right_bound_line;
LineString2d back_bound_line;

footprint_polygon.push_back({top_left_pos.x, top_left_pos.y});
footprint_polygon.push_back({top_right_pos.x, top_right_pos.y});
footprint_polygon.push_back({bottom_right_pos.x, bottom_right_pos.y});
footprint_polygon.push_back({bottom_left_pos.x, bottom_left_pos.y});

bg::correct(footprint_polygon);

for (const auto & p : left_bound) {
left_bound_line.push_back({p.x, p.y});
}

for (const auto & p : right_bound) {
right_bound_line.push_back({p.x, p.y});
}

back_bound_line = {left_bound_line.back(), right_bound_line.back()};

if (
bg::intersects(footprint_polygon, left_bound_line) ||
bg::intersects(footprint_polygon, right_bound_line) ||
bg::intersects(footprint_polygon, back_bound_line)) {
return true;
}

const bool front_top_left = isFrontDrivableArea(top_left_pos, left_bound, right_bound);
const bool front_top_right = isFrontDrivableArea(top_right_pos, left_bound, right_bound);
const bool front_bottom_left = isFrontDrivableArea(bottom_left_pos, left_bound, right_bound);
Expand Down

0 comments on commit 3c43118

Please sign in to comment.