Apollo  6.0
Open source self driving car software
preprocess_points_cuda.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2020 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 
17 /*
18  * Copyright 2018-2019 Autoware Foundation. All rights reserved.
19  *
20  * Licensed under the Apache License, Version 2.0 (the "License");
21  * you may not use this file except in compliance with the License.
22  * You may obtain a copy of the License at
23  *
24  * http://www.apache.org/licenses/LICENSE-2.0
25  *
26  * Unless required by applicable law or agreed to in writing, software
27  * distributed under the License is distributed on an "AS IS" BASIS,
28  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
29  * See the License for the specific language governing permissions and
30  * limitations under the License.
31  */
32 
40 #pragma once
41 
42 namespace apollo {
43 namespace perception {
44 namespace lidar {
45 
47  private:
48  // initializer list
49  const int num_threads_;
50  const int max_num_pillars_;
51  const int max_num_points_per_pillar_;
52  const int num_point_feature_;
53  const int num_inds_for_scan_;
54  const int grid_x_size_;
55  const int grid_y_size_;
56  const int grid_z_size_;
57  const float pillar_x_size_;
58  const float pillar_y_size_;
59  const float pillar_z_size_;
60  const float min_x_range_;
61  const float min_y_range_;
62  const float min_z_range_;
63  // end initializer list
64 
65  float* dev_pillar_point_feature_in_coors_;
66  int* dev_pillar_count_histo_;
67 
68  int* dev_counter_;
69  int* dev_pillar_count_;
70 
71  public:
90  PreprocessPointsCuda(const int num_threads, const int max_num_pillars,
91  const int max_points_per_pillar,
92  const int num_point_feature, const int num_inds_for_scan,
93  const int grid_x_size, const int grid_y_size,
94  const int grid_z_size, const float pillar_x_size,
95  const float pillar_y_size, const float pillar_z_size,
96  const float min_x_range, const float min_y_range,
97  const float min_z_range);
99 
117  void DoPreprocessPointsCuda(const float* dev_points, const int in_num_points,
118  int* dev_x_coors, int* dev_y_coors,
119  float* dev_num_points_per_pillar,
120  float* dev_pillar_point_feature,
121  float* dev_pillar_coors,
122  int* dev_sparse_pillar_map,
123  int* host_pillar_count);
124 };
125 
126 } // namespace lidar
127 } // namespace perception
128 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: preprocess_points_cuda.h:46
void DoPreprocessPointsCuda(const float *dev_points, const int in_num_points, int *dev_x_coors, int *dev_y_coors, float *dev_num_points_per_pillar, float *dev_pillar_point_feature, float *dev_pillar_coors, int *dev_sparse_pillar_map, int *host_pillar_count)
CUDA preprocessing for input point cloud.
PreprocessPointsCuda(const int num_threads, const int max_num_pillars, const int max_points_per_pillar, const int num_point_feature, const int num_inds_for_scan, const int grid_x_size, const int grid_y_size, const int grid_z_size, const float pillar_x_size, const float pillar_y_size, const float pillar_z_size, const float min_x_range, const float min_y_range, const float min_z_range)
Constructor.