From 5201e9d7cd113ff9768ab86a479352c845b14c6b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 30 Sep 2022 14:27:03 +0000 Subject: [PATCH] ci(pre-commit): autofix --- .../obstacle_avoidance_planner/src/node.cpp | 3 +- .../src/utils/cv_utils.cpp | 73 ++++++++++--------- 2 files changed, 39 insertions(+), 37 deletions(-) diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index ae0cef835f8c9..cc9acf5490fc4 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -961,8 +961,7 @@ std::vector ObstacleAvoidancePlanner::generateOptimizedTrajecto // insert 0 velocity when trajectory is over drivable area if (is_stopping_if_outside_drivable_area_) { - insertZeroVelocityOutsideDrivableArea( - planner_data, optimal_trajs.model_predictive_trajectory); + insertZeroVelocityOutsideDrivableArea(planner_data, optimal_trajs.model_predictive_trajectory); } publishDebugDataInOptimization(planner_data, optimal_trajs.model_predictive_trajectory); diff --git a/planning/obstacle_avoidance_planner/src/utils/cv_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/cv_utils.cpp index 985a24fbf29f1..1d2845fe4c07b 100644 --- a/planning/obstacle_avoidance_planner/src/utils/cv_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/cv_utils.cpp @@ -18,22 +18,22 @@ #include "tf2/utils.h" #include "tier4_autoware_utils/system/stop_watch.hpp" +#include +#include + #include "autoware_auto_perception_msgs/msg/predicted_object.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" #include "boost/optional.hpp" -#include - #include #include #include + #include +#include #include #include -#include -#include - namespace bg = boost::geometry; using point = bg::model::d2::point_xy; using polygon = bg::model::polygon; @@ -436,40 +436,43 @@ bool isOutsideDrivableAreaFromRectangleFootprint( footprint.outer().push_back(fp); const auto top_right_pos = tier4_autoware_utils::calcOffsetPose(traj_point.pose, base_to_front, half_width, 0.0).position; - fp = {top_right_pos.x, top_right_pos.y}; - footprint.outer().push_back(fp); + fp = {top_right_pos.x, top_right_pos.y}; + footprint.outer().push_back(fp); const auto bottom_right_pos = tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, half_width, 0.0).position; - fp = {bottom_right_pos.x, bottom_right_pos.y}; - footprint.outer().push_back(fp); + fp = {bottom_right_pos.x, bottom_right_pos.y}; + footprint.outer().push_back(fp); const auto bottom_left_pos = tier4_autoware_utils::calcOffsetPose(traj_point.pose, -base_to_rear, -half_width, 0.0).position; - fp = {bottom_left_pos.x, bottom_left_pos.y}; - - footprint.outer().push_back(fp); - - std::vector result; - cv::Mat cv_image; - grid_map::GridMap grid_map; - grid_map::GridMapRosConverter::fromOccupancyGrid(drivable_area, "layer", grid_map); - grid_map::GridMapCvConverter::toImage(grid_map, "layer", CV_8UC1, 0, 100, cv_image); - cv::dilate(cv_image, cv_image, cv::Mat(), cv::Point(-1, -1), 2); - cv::erode(cv_image, cv_image, cv::Mat(), cv::Point(-1, -1), 2); - std::vector> contours; - cv::findContours(cv_image, contours, CV_RETR_LIST, CV_CHAIN_APPROX_SIMPLE); - const auto & info = drivable_area.info; - for (const auto & contour : contours) { - point p; - for (const auto & point : contour) { - p = {(info.width - 1.0 - point.y) * info.resolution + info.origin.position.x, (info.height - 1.0 - point.x) * info.resolution + info.origin.position.y}; - } - drivable_area_polygon.outer().push_back(p); - } - bg::intersection(footprint, drivable_area_polygon, result); - - if (result.size == 1) { - return true; - } + fp = {bottom_left_pos.x, bottom_left_pos.y}; + + footprint.outer().push_back(fp); + + std::vector result; + cv::Mat cv_image; + grid_map::GridMap grid_map; + grid_map::GridMapRosConverter::fromOccupancyGrid(drivable_area, "layer", grid_map); + grid_map::GridMapCvConverter::toImage( + grid_map, "layer", CV_8UC1, 0, 100, cv_image); + cv::dilate(cv_image, cv_image, cv::Mat(), cv::Point(-1, -1), 2); + cv::erode(cv_image, cv_image, cv::Mat(), cv::Point(-1, -1), 2); + std::vector> contours; + cv::findContours(cv_image, contours, CV_RETR_LIST, CV_CHAIN_APPROX_SIMPLE); + const auto & info = drivable_area.info; + for (const auto & contour : contours) { + point p; + for (const auto & point : contour) { + p = { + (info.width - 1.0 - point.y) * info.resolution + info.origin.position.x, + (info.height - 1.0 - point.x) * info.resolution + info.origin.position.y}; + } + drivable_area_polygon.outer().push_back(p); + } + bg::intersection(footprint, drivable_area_polygon, result); + + if (result.size == 1) { + return true; + } return false; }