22 #include "gtest/gtest_prod.h" 24 #include "modules/perception/lidar/lib/detector/cnn_segmentation/proto/cnnseg_param.pb.h" 30 namespace perception {
37 pc_gpu_size_ = kMaxPointCloudGPUSize;
38 BASE_CUDA_CHECK(cudaMalloc(reinterpret_cast<void**>(&pc_gpu_),
40 BASE_CUDA_CHECK(cudaMalloc(reinterpret_cast<void**>(&point2grid_gpu_),
41 pc_gpu_size_ *
sizeof(
int)));
54 const std::vector<int>& point2grid) {
56 GenerateGPU(pc_ptr, point2grid);
58 GenerateCPU(pc_ptr, point2grid);
62 inline std::string
Name()
const {
return "FeatureGenerator"; }
67 const std::vector<int>& point2grid);
68 void ReleaseGPUMemory();
71 const std::vector<int>& point2grid);
73 float LogCount(
int count) {
74 if (count < static_cast<int>(log_table_.size())) {
75 return log_table_[count];
77 return logf(static_cast<float>(1 + count));
81 std::vector<float> log_table_;
83 std::shared_ptr<base::Blob<float>> log_blob_;
84 const int kMaxLogNum = 256;
90 float min_height_ = 0.0f;
91 float max_height_ = 0.0f;
92 bool use_intensity_feature_ =
false;
93 bool use_constant_feature_ =
false;
96 float* max_height_data_ =
nullptr;
97 float* mean_height_data_ =
nullptr;
98 float* count_data_ =
nullptr;
99 float* direction_data_ =
nullptr;
100 float* top_intensity_data_ =
nullptr;
101 float* mean_intensity_data_ =
nullptr;
102 float* distance_data_ =
nullptr;
103 float* nonempty_data_ =
nullptr;
106 std::vector<int> map_idx_;
113 int* point2grid_gpu_ =
nullptr;
114 int pc_gpu_size_ = 0;
115 const int kMaxPointCloudGPUSize = 120000;
116 const int kGPUThreadSize = 512;
friend class FeatureGeneratorTest
Definition: feature_generator.h:120
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: feature_generator.h:33
virtual ~FeatureGenerator()
Definition: feature_generator.h:45
bool Init(const FeatureParam &feature_param, base::Blob< float > *out_blob)
FeatureGenerator()
Definition: feature_generator.h:35
void Generate(const base::PointFCloudPtr &pc_ptr, const std::vector< int > &point2grid)
Definition: feature_generator.h:53
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:482
std::string Name() const
Definition: feature_generator.h:62