Skip to content

Commit

Permalink
ci(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jan 17, 2023
1 parent 13ea0bd commit a80b91e
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -156,4 +156,4 @@
bicycle_model:
num_for_calculation: 3
front_radius_ratio: 1.0
rear_radius_ratio: 1.0
rear_radius_ratio: 1.0
23 changes: 12 additions & 11 deletions planning/obstacle_avoidance_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ typedef bg::model::polygon<bg_point> bg_polygon;
namespace
{
namespace bg = boost::geometry;
using tier4_autoware_utils::LineString2d;
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 @@ -721,23 +721,24 @@ bool isOutsideDrivableAreaFromRectangleFootprint(
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);
bg::correct(footprint_polygon);

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

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

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

if(bg::intersects(footprint_polygon, left_bound_line) ||
bg::intersects(footprint_polygon, right_bound_line) ||
bg::intersects(footprint_polygon, back_bound_line)) {
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);
Expand Down

0 comments on commit a80b91e

Please sign in to comment.