Skip to content

Commit 6edc7fd

Browse files
style(pre-commit): autofix
1 parent 41864cd commit 6edc7fd

File tree

1 file changed

+10
-7
lines changed

1 file changed

+10
-7
lines changed

planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp

+10-7
Original file line numberDiff line numberDiff line change
@@ -242,7 +242,8 @@ void categorizeVehicles(
242242
return;
243243
}
244244

245-
lanelet::ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineString2d & ll_string)
245+
lanelet::ArcCoordinates getOcclusionPoint(
246+
const PredictedObject & obj, const ConstLineString2d & ll_string)
246247
{
247248
const auto poly = tier4_autoware_utils::toPolygon2d(obj);
248249
std::deque<lanelet::ArcCoordinates> arcs;
@@ -257,16 +258,18 @@ lanelet::ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const Con
257258
* Ego===============> path
258259
**/
259260
// sort by arc length
260-
std::sort(arcs.begin(), arcs.end(), [](lanelet::ArcCoordinates arc1, lanelet::ArcCoordinates arc2) {
261-
return arc1.length < arc2.length;
262-
});
261+
std::sort(
262+
arcs.begin(), arcs.end(), [](lanelet::ArcCoordinates arc1, lanelet::ArcCoordinates arc2) {
263+
return arc1.length < arc2.length;
264+
});
263265
// remove closest 2 polygon point
264266
arcs.pop_front();
265267
arcs.pop_front();
266268
// sort by arc distance
267-
std::sort(arcs.begin(), arcs.end(), [](lanelet::ArcCoordinates arc1, lanelet::ArcCoordinates arc2) {
268-
return std::abs(arc1.distance) < std::abs(arc2.distance);
269-
});
269+
std::sort(
270+
arcs.begin(), arcs.end(), [](lanelet::ArcCoordinates arc1, lanelet::ArcCoordinates arc2) {
271+
return std::abs(arc1.distance) < std::abs(arc2.distance);
272+
});
270273
// return closest to path point which is choosen by farthest 2 points.
271274
return arcs.at(0);
272275
}

0 commit comments

Comments
 (0)