From d9d3164cd1217db348887c8c5c2b22c625d61c3b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 22 Aug 2024 13:48:44 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../autoware/autonomous_emergency_braking/node.hpp | 8 +++++--- .../autoware_autonomous_emergency_braking/src/node.cpp | 9 +++++---- 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index 692c1a0fa0a98..d1da770f7f465 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -395,7 +395,8 @@ class AEB : public rclcpp::Node * @return True if a collision is detected, false otherwise */ bool hasCollision( - const double current_v, const ObjectData & closest_object, const std::vector & ego_polys); + const double current_v, const ObjectData & closest_object, + const std::vector & ego_polys); /** * @brief Generate the ego vehicle path @@ -467,9 +468,10 @@ class AEB : public rclcpp::Node */ void addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, - const std::vector & search_area_polygons,const std::vector & objects, + const std::vector & search_area_polygons, const std::vector & objects, const std::optional & closest_object, const double color_r, const double color_g, - const double color_b, const double color_a, const std::string & ns, MarkerArray & debug_markers); + const double color_b, const double color_a, const std::string & ns, + MarkerArray & debug_markers); /** * @brief Add a collision marker for debugging diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 02944f5df2f0b..db3e7d960718b 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -486,8 +486,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers) if (publish_debug_markers_) { const auto [color_r, color_g, color_b, color_a] = debug_colors; addMarker( - this->get_clock()->now(), path, ego_polys, expanded_ego_polys, objects, closest_object_point, color_r, color_g, - color_b, color_a, debug_ns, debug_markers); + this->get_clock()->now(), path, ego_polys, expanded_ego_polys, objects, + closest_object_point, color_r, color_g, color_b, color_a, debug_ns, debug_markers); } // check collision using rss distance return (closest_object_point.has_value()) @@ -538,7 +538,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers) } bool AEB::hasCollision( - const double current_v, const ObjectData & closest_object, const std::vector & ego_polys) + const double current_v, const ObjectData & closest_object, + const std::vector & ego_polys) { const Point2d obj_point(closest_object.position.x, closest_object.position.y); bool is_point_inside = false; @@ -875,7 +876,7 @@ void AEB::cropPointCloudWithEgoFootprintPath( void AEB::addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, - const std::vector & search_area_polygons,const std::vector & objects, + const std::vector & search_area_polygons, const std::vector & objects, const std::optional & closest_object, const double color_r, const double color_g, const double color_b, const double color_a, const std::string & ns, MarkerArray & debug_markers) {