@@ -129,8 +129,6 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
129
129
publish_debug_pointcloud_ = declare_parameter<bool >(" publish_debug_pointcloud" );
130
130
use_predicted_trajectory_ = declare_parameter<bool >(" use_predicted_trajectory" );
131
131
use_imu_path_ = declare_parameter<bool >(" use_imu_path" );
132
- crop_pointcloud_with_path_footprint_ =
133
- declare_parameter<bool >(" crop_pointcloud_with_path_footprint" );
134
132
path_footprint_extra_margin_ = declare_parameter<double >(" path_footprint_extra_margin" );
135
133
detection_range_min_height_ = declare_parameter<double >(" detection_range_min_height" );
136
134
detection_range_max_height_margin_ =
@@ -334,11 +332,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
334
332
const auto ego_path = generateEgoPath (current_v, current_w);
335
333
336
334
// Crop out Pointcloud using an extra wide ego path
337
- if (crop_pointcloud_with_path_footprint_) {
338
- const auto expanded_ego_polys =
339
- generatePathFootprint (ego_path, expand_width_ + path_footprint_extra_margin_);
340
- cropPointCloudWithEgoFootprintPath (expanded_ego_polys);
341
- }
335
+ const auto expanded_ego_polys =
336
+ generatePathFootprint (ego_path, expand_width_ + path_footprint_extra_margin_);
337
+ cropPointCloudWithEgoFootprintPath (expanded_ego_polys);
342
338
343
339
std::vector<ObjectData> objects_from_point_clusters;
344
340
const auto ego_polys = generatePathFootprint (ego_path, expand_width_);
@@ -366,11 +362,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
366
362
const auto & predicted_path = predicted_path_opt.value ();
367
363
368
364
// Crop out Pointcloud using an extra wide ego path
369
- if (crop_pointcloud_with_path_footprint_) {
370
- const auto expanded_ego_polys =
371
- generatePathFootprint (predicted_path, expand_width_ + path_footprint_extra_margin_);
372
- cropPointCloudWithEgoFootprintPath (expanded_ego_polys);
373
- }
365
+ const auto expanded_ego_polys =
366
+ generatePathFootprint (predicted_path, expand_width_ + path_footprint_extra_margin_);
367
+ cropPointCloudWithEgoFootprintPath (expanded_ego_polys);
374
368
375
369
std::vector<ObjectData> objects_from_point_clusters;
376
370
const auto predicted_polys = generatePathFootprint (predicted_path, expand_width_);
0 commit comments