Skip to content

Commit 822fc56

Browse files
pre-commit-ci[bot]beyza
authored and
beyza
committed
style(pre-commit): autofix
1 parent 52cfdc9 commit 822fc56

File tree

3 files changed

+12
-13
lines changed

3 files changed

+12
-13
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp

+8-10
Original file line numberDiff line numberDiff line change
@@ -73,17 +73,15 @@ std::vector<Collision> find_collisions(
7373
std::optional<geometry_msgs::msg::Point> collision;
7474
for (auto object_idx = 0UL; object_idx < objects.size(); ++object_idx) {
7575
const auto & object_pose = objects[object_idx].kinematics.initial_pose_with_covariance.pose;
76-
if (!params.ignore_objects_behind_ego){
77-
tier4_autoware_utils::MultiPolygon2d object_footprint;
78-
for (const auto &polygon : object_forward_footprints) {
79-
object_footprint.push_back(polygon);
80-
collision =
81-
find_closest_collision_point(ego_data, object_pose, polygon, params);
82-
}
76+
if (!params.ignore_objects_behind_ego) {
77+
tier4_autoware_utils::MultiPolygon2d object_footprint;
78+
for (const auto & polygon : object_forward_footprints) {
79+
object_footprint.push_back(polygon);
80+
collision = find_closest_collision_point(ego_data, object_pose, polygon, params);
81+
}
8382
} else {
84-
const auto &object_footprint = object_forward_footprints[object_idx];
85-
collision =
86-
find_closest_collision_point(ego_data, object_pose, object_footprint, params);
83+
const auto & object_footprint = object_forward_footprints[object_idx];
84+
collision = find_closest_collision_point(ego_data, object_pose, object_footprint, params);
8785
}
8886
if (collision) {
8987
Collision c;

planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,8 @@ DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node
3131
auto & pp = planner_param_;
3232

3333
pp.extra_object_width = getOrDeclareParameter<double>(node, ns + ".extra_object_width");
34-
pp.extra_object_footprint_width = getOrDeclareParameter<double>(node, ns + ".extra_object_footprint_width");
34+
pp.extra_object_footprint_width =
35+
getOrDeclareParameter<double>(node, ns + ".extra_object_footprint_width");
3536
pp.minimum_object_velocity = getOrDeclareParameter<double>(node, ns + ".minimum_object_velocity");
3637
pp.stop_distance_buffer = getOrDeclareParameter<double>(node, ns + ".stop_distance_buffer");
3738
pp.time_horizon = getOrDeclareParameter<double>(node, ns + ".time_horizon");

planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,8 @@ std::vector<autoware_perception_msgs::msg::PredictedObject> filter_predicted_obj
6060
std::abs(obj_arc_length) <
6161
params.behind_object_distance_threshold + o.shape.dimensions.x / 2.0) ||
6262
(obj_arc_length > o.shape.dimensions.x / 2.0 ||
63-
obj_arc_length > ego_data.longitudinal_offset_to_first_path_idx +
64-
params.ego_longitudinal_offset + o.shape.dimensions.x / 2.0);
63+
obj_arc_length > ego_data.longitudinal_offset_to_first_path_idx +
64+
params.ego_longitudinal_offset + o.shape.dimensions.x / 2.0);
6565
}
6666
return obj_arc_length > ego_data.longitudinal_offset_to_first_path_idx +
6767
params.ego_longitudinal_offset + o.shape.dimensions.x / 2.0;

0 commit comments

Comments
 (0)