Apollo  6.0
Open source self driving car software
feature_generator.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "gtest/gtest_prod.h"
23 
24 #include "modules/perception/lidar/lib/detector/cnn_segmentation/proto/cnnseg_param.pb.h"
25 
28 
29 namespace apollo {
30 namespace perception {
31 namespace lidar {
32 
34  public:
36 #if USE_GPU == 1
37  pc_gpu_size_ = kMaxPointCloudGPUSize;
38  BASE_CUDA_CHECK(cudaMalloc(reinterpret_cast<void**>(&pc_gpu_),
39  pc_gpu_size_ * sizeof(base::PointF)));
40  BASE_CUDA_CHECK(cudaMalloc(reinterpret_cast<void**>(&point2grid_gpu_),
41  pc_gpu_size_ * sizeof(int)));
42 #endif
43  }
44 
45  virtual ~FeatureGenerator() {
46 #if USE_GPU == 1
47  ReleaseGPUMemory();
48 #endif
49  }
50 
51  bool Init(const FeatureParam& feature_param, base::Blob<float>* out_blob);
52 
53  void Generate(const base::PointFCloudPtr& pc_ptr,
54  const std::vector<int>& point2grid) {
55 #if USE_GPU == 1
56  GenerateGPU(pc_ptr, point2grid);
57 #else
58  GenerateCPU(pc_ptr, point2grid);
59 #endif
60  }
61 
62  inline std::string Name() const { return "FeatureGenerator"; }
63 
64  private:
65 #if USE_GPU == 1
66  void GenerateGPU(const base::PointFCloudPtr& pc_ptr,
67  const std::vector<int>& point2grid);
68  void ReleaseGPUMemory();
69 #endif
70  void GenerateCPU(const base::PointFCloudPtr& pc_ptr,
71  const std::vector<int>& point2grid);
72 
73  float LogCount(int count) {
74  if (count < static_cast<int>(log_table_.size())) {
75  return log_table_[count];
76  }
77  return logf(static_cast<float>(1 + count));
78  }
79 
80  // log table for CPU, with std::vector type
81  std::vector<float> log_table_;
82  // log table for GPU, with base::Blob type
83  std::shared_ptr<base::Blob<float>> log_blob_;
84  const int kMaxLogNum = 256;
85 
86  // feature param
87  int width_ = 0;
88  int height_ = 0;
89  float range_ = 0.0f;
90  float min_height_ = 0.0f;
91  float max_height_ = 0.0f;
92  bool use_intensity_feature_ = false;
93  bool use_constant_feature_ = false;
94 
95  // raw feature data
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;
104 
105  // 1-d index in feature map of each point
106  std::vector<int> map_idx_;
107 
108  // output feature blob
109  base::Blob<float>* out_blob_ = nullptr;
110 
111  // param for managing gpu memory, only for cuda code
112  base::PointF* pc_gpu_ = nullptr;
113  int* point2grid_gpu_ = nullptr;
114  int pc_gpu_size_ = 0;
115  const int kMaxPointCloudGPUSize = 120000;
116  const int kGPUThreadSize = 512;
117 
118  // for TEST only
119  FRIEND_TEST(FeatureGeneratorTest, basic_test);
120  friend class FeatureGeneratorTest;
121 };
122 
123 } // namespace lidar
124 } // namespace perception
125 } // namespace apollo
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: point.h:28
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