Skip to content

Commit

Permalink
Perception: add cropping point cloud and ground removal
Browse files Browse the repository at this point in the history
  • Loading branch information
jeroldchen authored and jinghaomiao committed Sep 1, 2020
1 parent 3180885 commit 164c08a
Show file tree
Hide file tree
Showing 5 changed files with 84 additions and 5 deletions.
2 changes: 2 additions & 0 deletions modules/perception/common/perception_gflags.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ DEFINE_double(normalizing_factor, 255,
DEFINE_int32(num_point_feature, 5,
"Length of raw point feature. Features include x, y, z,"
"intensity and delta of time.");
DEFINE_bool(enable_ground_removal, false, "Enable ground removal.");
DEFINE_double(ground_removal_height, -1.5, "Height for ground removal.");
DEFINE_bool(enable_downsample_beams, false,
"Enable down sampling point cloud beams with a factor.");
DEFINE_int32(downsample_beams_factor, 4,
Expand Down
2 changes: 2 additions & 0 deletions modules/perception/common/perception_gflags.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ DECLARE_string(pfe_onnx_file);
DECLARE_string(rpn_onnx_file);
DECLARE_double(normalizing_factor);
DECLARE_int32(num_point_feature);
DECLARE_bool(enable_ground_removal);
DECLARE_double(ground_removal_height);
DECLARE_bool(enable_downsample_beams);
DECLARE_int32(downsample_beams_factor);
DECLARE_bool(enable_downsample_pointcloud);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include "modules/perception/common/perception_gflags.h"
#include "modules/perception/lidar/common/lidar_timer.h"
#include "modules/perception/lidar/common/pcl_util.h"
#include "modules/perception/lidar/lib/detection/lidar_point_pillars/params.h"

namespace apollo {
namespace perception {
Expand All @@ -43,6 +44,18 @@ bool PointPillarsDetection::Init(const DetectionInitOptions& options) {
point_pillars_ptr_.reset(new PointPillars(
FLAGS_reproduce_result_mode, FLAGS_score_threshold,
FLAGS_nms_overlap_threshold, FLAGS_pfe_onnx_file, FLAGS_rpn_onnx_file));

// point cloud range
x_min_ = Params::kMinXRange;
x_max_ = Params::kMaxXRange;
y_min_ = Params::kMinYRange;
y_max_ = Params::kMaxYRange;
z_min_ = Params::kMinZRange;
z_max_ = Params::kMaxZRange;
if (FLAGS_enable_ground_removal) {
z_min_ = std::max(z_min_, static_cast<float>(FLAGS_ground_removal_height));
}

return true;
}

Expand Down Expand Up @@ -88,7 +101,7 @@ bool PointPillarsDetection::Detect(const DetectionOptions& options,
FLAGS_downsample_beams_factor)) {
cur_cloud_ptr_ = downsample_beams_cloud_ptr;
} else {
AWARN << "Down sample beams factor must be >= 1. Cancel down sampling."
AWARN << "Down-sample beams factor must be >= 1. Cancel down-sampling."
" Current factor: "
<< FLAGS_downsample_beams_factor;
}
Expand Down Expand Up @@ -202,11 +215,19 @@ void PointPillarsDetection::CloudToArray(const base::PointFCloudPtr& pc_ptr,
const float normalizing_factor) {
for (size_t i = 0; i < pc_ptr->size(); ++i) {
const auto& point = pc_ptr->at(i);
out_points_array[i * FLAGS_num_point_feature + 0] = point.x;
out_points_array[i * FLAGS_num_point_feature + 1] = point.y;
out_points_array[i * FLAGS_num_point_feature + 2] = point.z;
float x = point.x;
float y = point.y;
float z = point.z;
float intensity = point.intensity;
if (z < z_min_ || z > z_max_ || y < y_min_ || y > y_max_ || x < x_min_ ||
x > x_max_) {
continue;
}
out_points_array[i * FLAGS_num_point_feature + 0] = x;
out_points_array[i * FLAGS_num_point_feature + 1] = y;
out_points_array[i * FLAGS_num_point_feature + 2] = z;
out_points_array[i * FLAGS_num_point_feature + 3] =
point.intensity / normalizing_factor;
intensity / normalizing_factor;
// delta of timestamp between prev and cur frames
out_points_array[i * FLAGS_num_point_feature + 4] =
static_cast<float>(pc_ptr->points_timestamp(i));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,14 @@ class PointPillarsDetection {
std::deque<base::PointDCloudPtr> prev_world_clouds_;
base::PointFCloudPtr cur_cloud_ptr_;

// point cloud range
float x_min_;
float x_max_;
float y_min_;
float y_max_;
float z_min_;
float z_max_;

// time statistics
double downsample_time_ = 0.0;
double fuse_time_ = 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,12 +88,58 @@

###########################################################################
# Flags from lidar_point_pillars

# classification score threshold
# type: double
# default: 0.5
--score_threshold=0.5

# enable ground removal
# type: bool
# default: false
--enable_ground_removal=false

# remove point cloud that under this height
# type: double
# default: -1.5
--ground_removal_height=-1.5

# enable down-sample point cloud by beams
# type: bool
# default: false
--enable_downsample_beams=false

# factor for down-sampling point cloud beams
# type: int
# default: 4
--downsample_beams_factor=4

# enable down-sample point cloud by voxelization
# type: bool
# default: false
--enable_downsample_pointcloud=false

# down-sample voxel size along x-axis
# type: double
# default: 0.01
--downsample_voxel_size_x=0.1

# down-sample voxel size along y-axis
# type: double
# default: 0.01
--downsample_voxel_size_y=0.1

# down-sample voxel size along z-axis
# type: double
# default: 0.01
--downsample_voxel_size_z=0.1

# enable fusing point cloud of preceding frames
# type: bool
# default: false
--enable_fuse_frames=false

# number of frames (including current frame) for fusing point cloud
# type: int
# default: 5
--num_fuse_frames=5

0 comments on commit 164c08a

Please sign in to comment.