Skip to content

Commit 16b6ee2

Browse files
remove problematic option
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent eabeeea commit 16b6ee2

File tree

3 files changed

+6
-14
lines changed

3 files changed

+6
-14
lines changed

control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
publish_debug_pointcloud: false
44
use_predicted_trajectory: true
55
use_imu_path: true
6-
crop_pointcloud_with_path_footprint: true
76
path_footprint_extra_margin: 1.0
87
detection_range_min_height: 0.0
98
detection_range_max_height_margin: 0.0

control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -185,7 +185,6 @@ class AEB : public rclcpp::Node
185185
bool publish_debug_pointcloud_;
186186
bool use_predicted_trajectory_;
187187
bool use_imu_path_;
188-
bool crop_pointcloud_with_path_footprint_;
189188
double path_footprint_extra_margin_;
190189
double detection_range_min_height_;
191190
double detection_range_max_height_margin_;

control/autonomous_emergency_braking/src/node.cpp

+6-12
Original file line numberDiff line numberDiff line change
@@ -129,8 +129,6 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
129129
publish_debug_pointcloud_ = declare_parameter<bool>("publish_debug_pointcloud");
130130
use_predicted_trajectory_ = declare_parameter<bool>("use_predicted_trajectory");
131131
use_imu_path_ = declare_parameter<bool>("use_imu_path");
132-
crop_pointcloud_with_path_footprint_ =
133-
declare_parameter<bool>("crop_pointcloud_with_path_footprint");
134132
path_footprint_extra_margin_ = declare_parameter<double>("path_footprint_extra_margin");
135133
detection_range_min_height_ = declare_parameter<double>("detection_range_min_height");
136134
detection_range_max_height_margin_ =
@@ -334,11 +332,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
334332
const auto ego_path = generateEgoPath(current_v, current_w);
335333

336334
// 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);
342338

343339
std::vector<ObjectData> objects_from_point_clusters;
344340
const auto ego_polys = generatePathFootprint(ego_path, expand_width_);
@@ -366,11 +362,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
366362
const auto & predicted_path = predicted_path_opt.value();
367363

368364
// 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);
374368

375369
std::vector<ObjectData> objects_from_point_clusters;
376370
const auto predicted_polys = generatePathFootprint(predicted_path, expand_width_);

0 commit comments

Comments
 (0)