Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] authored and ismetatabay committed Aug 23, 2024
1 parent b17e6eb commit d9d3164
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<Polygon2d> & ego_polys);
const double current_v, const ObjectData & closest_object,
const std::vector<Polygon2d> & ego_polys);

/**
* @brief Generate the ego vehicle path
Expand Down Expand Up @@ -467,9 +468,10 @@ class AEB : public rclcpp::Node
*/
void addMarker(
const rclcpp::Time & current_time, const Path & path, const std::vector<Polygon2d> & polygons,
const std::vector<Polygon2d> & search_area_polygons,const std::vector<ObjectData> & objects,
const std::vector<Polygon2d> & search_area_polygons, const std::vector<ObjectData> & objects,
const std::optional<ObjectData> & 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
Expand Down
9 changes: 5 additions & 4 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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())
Expand Down Expand Up @@ -538,7 +538,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
}

bool AEB::hasCollision(
const double current_v, const ObjectData & closest_object, const std::vector<Polygon2d> & ego_polys)
const double current_v, const ObjectData & closest_object,
const std::vector<Polygon2d> & ego_polys)
{
const Point2d obj_point(closest_object.position.x, closest_object.position.y);
bool is_point_inside = false;
Expand Down Expand Up @@ -875,7 +876,7 @@ void AEB::cropPointCloudWithEgoFootprintPath(

void AEB::addMarker(
const rclcpp::Time & current_time, const Path & path, const std::vector<Polygon2d> & polygons,
const std::vector<Polygon2d> & search_area_polygons,const std::vector<ObjectData> & objects,
const std::vector<Polygon2d> & search_area_polygons, const std::vector<ObjectData> & objects,
const std::optional<ObjectData> & 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)
{
Expand Down

0 comments on commit d9d3164

Please sign in to comment.