Skip to content

Commit 49311e4

Browse files
committed
feat(AEB): add max height range in AEB
Signed-off-by: Shin-kyoto <aquashin0202@gmail.com>
1 parent 27e5f8d commit 49311e4

File tree

4 files changed

+28
-21
lines changed

4 files changed

+28
-21
lines changed

control/autonomous_emergency_braking/README.md

+21-20
Original file line numberDiff line numberDiff line change
@@ -26,26 +26,27 @@ This module has following assumptions.
2626

2727
## Parameters
2828

29-
| Name | Unit | Type | Description | Default value |
30-
| :--------------------------- | :----- | :----- | :------------------------------------------------------------------------------------------------ | :------------ |
31-
| publish_debug_pointcloud | [-] | bool | flag to publish the point cloud used for debugging | false |
32-
| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true |
33-
| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true |
34-
| detection_range_min_height | [m] | double | minimum hight of detection range used for avoiding the ghost brake by false positive point clouds | 0.3 |
35-
| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 |
36-
| voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 |
37-
| voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 |
38-
| min_generated_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 |
39-
| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 |
40-
| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 |
41-
| t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 |
42-
| a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 |
43-
| a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 |
44-
| imu_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 |
45-
| imu_prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 |
46-
| mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 |
47-
| mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 |
48-
| aeb_hz | [-] | double | frequency at which AEB operates per second | 10 |
29+
| Name | Unit | Type | Description | Default value |
30+
| :-------------------------------- | :----- | :----- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
31+
| publish_debug_pointcloud | [-] | bool | flag to publish the point cloud used for debugging | false |
32+
| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true |
33+
| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true |
34+
| detection_range_min_height | [m] | double | minimum hight of detection range used for avoiding the ghost brake by false positive point clouds | 0.3 |
35+
| detection_range_max_height_margin | [m] | double | margin for maximum hight of detection range used for avoiding the ghost brake by false positive point clouds. `detection_range_max_height = vehicle_height + detection_range_max_height_margin` | 0.0 |
36+
| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 |
37+
| voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 |
38+
| voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 |
39+
| min_generated_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 |
40+
| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 |
41+
| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 |
42+
| t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 |
43+
| a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 |
44+
| a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 |
45+
| imu_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 |
46+
| imu_prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 |
47+
| mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 |
48+
| mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 |
49+
| aeb_hz | [-] | double | frequency at which AEB operates per second | 10 |
4950

5051
## Inner-workings / Algorithms
5152

control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
use_predicted_trajectory: true
55
use_imu_path: true
66
detection_range_min_height: 0.3
7+
detection_range_max_height_margin: 0.0
78
voxel_grid_x: 0.05
89
voxel_grid_y: 0.05
910
voxel_grid_z: 100000.0

control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -176,6 +176,7 @@ class AEB : public rclcpp::Node
176176
bool use_predicted_trajectory_;
177177
bool use_imu_path_;
178178
double detection_range_min_height_;
179+
double detection_range_max_height_margin_;
179180
double voxel_grid_x_;
180181
double voxel_grid_y_;
181182
double voxel_grid_z_;

control/autonomous_emergency_braking/src/node.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,8 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
130130
use_predicted_trajectory_ = declare_parameter<bool>("use_predicted_trajectory");
131131
use_imu_path_ = declare_parameter<bool>("use_imu_path");
132132
detection_range_min_height_ = declare_parameter<double>("detection_range_min_height");
133+
detection_range_max_height_margin_ =
134+
declare_parameter<double>("detection_range_max_height_margin");
133135
voxel_grid_x_ = declare_parameter<double>("voxel_grid_x");
134136
voxel_grid_y_ = declare_parameter<double>("voxel_grid_y");
135137
voxel_grid_z_ = declare_parameter<double>("voxel_grid_z");
@@ -228,7 +230,9 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg)
228230
pcl::PassThrough<pcl::PointXYZ> height_filter;
229231
height_filter.setInputCloud(pointcloud_ptr);
230232
height_filter.setFilterFieldName("z");
231-
height_filter.setFilterLimits(detection_range_min_height_, 5.0);
233+
height_filter.setFilterLimits(
234+
detection_range_min_height_,
235+
vehicle_info_.vehicle_height_m + detection_range_max_height_margin_);
232236
height_filter.filter(*height_filtered_pointcloud_ptr);
233237

234238
pcl::VoxelGrid<pcl::PointXYZ> filter;

0 commit comments

Comments
 (0)