@@ -252,15 +252,27 @@ double calc_obstacle_min_length(const Shape & shape);
252
252
double calc_obstacle_max_length (const Shape & shape);
253
253
254
254
/* *
255
- * @brief Calculate collision roughly by comparing minimum/maximum distance with margin.
256
- * @param path The path of the ego vehicle.
257
- * @param objects The predicted objects.
258
- * @param min_margin_threshold threshold for collision check when the minimum distance between ego
259
- * @param max_margin_threshold threshold for collision check when the maximum distance between ego
260
- * @param parameters The common parameters used in behavior path planner.
261
- * @param use_offset_ego_point If true, the closest point to the object is calculated by
262
- * interpolating the path points.
263
- * @return Collision (rough) between minimum distance and maximum distance
255
+ * @brief Performs efficient rough collision detection between ego vehicle and objects
256
+ * @details
257
+ * This function calculates two types of distances between ego vehicle and each object:
258
+ * - Minimum distance: The shortest possible distance between ego and object when positioned
259
+ * diagonally with their corners closest to each other (uses maximum extent of both objects)
260
+ * - Maximum distance: The largest possible distance between ego and object when positioned parallel
261
+ * to each other (uses minimum extent of both objects)
262
+ *
263
+ * A collision is detected when:
264
+ * - min_distance < min_margin_threshold (first element of returned pair is true)
265
+ * - max_distance < max_margin_threshold (second element of returned pair is true)
266
+ *
267
+ * This approach provides a computationally efficient rough collision check that can be used
268
+ * before performing more expensive precise collision detection algorithms.
269
+ * @param path The path of the ego vehicle
270
+ * @param objects The predicted objects to check for collision
271
+ * @param min_margin_threshold Threshold for minimum distance collision check
272
+ * @param max_margin_threshold Threshold for maximum distance collision check
273
+ * @param parameters The common parameters used in behavior path planner
274
+ * @param use_offset_ego_point If true, uses interpolated point on path closest to object
275
+ * @return A pair of boolean values {min_distance_collision, max_distance_collision}
264
276
*/
265
277
std::pair<bool , bool > checkObjectsCollisionRough (
266
278
const PathWithLaneId & path, const PredictedObjects & objects, const double min_margin_threshold,
0 commit comments