Apollo  6.0
Open source self driving car software
mask_pillars_detection.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2021 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 <deque>
19 #include <memory>
20 #include <string>
21 #include <vector>
22 
23 #include "pcl/point_cloud.h"
24 #include "pcl/point_types.h"
25 
31 
32 namespace apollo {
33 namespace perception {
34 namespace lidar {
35 
37  public:
39  virtual ~MaskPillarsDetection() = default;
40 
41  bool Init(const LidarDetectorInitOptions& options =
42  LidarDetectorInitOptions()) override;
43 
44  bool Detect(const LidarDetectorOptions& options, LidarFrame* frame) override;
45 
46  std::string Name() const override { return "MaskPillarsDetection"; }
47 
48  private:
49  void CloudToArray(const base::PointFCloudPtr& pc_ptr, float* out_points_array,
50  float normalizing_factor);
51 
52  void FuseCloud(const base::PointFCloudPtr& out_cloud_ptr,
53  const std::deque<base::PointDCloudPtr>& fuse_clouds);
54 
55  std::vector<int> GenerateIndices(int start_index, int size, bool shuffle);
56 
57  void GetObjects(std::vector<std::shared_ptr<base::Object>>* objects,
58  const Eigen::Affine3d& pose, std::vector<float>* detections,
59  std::vector<int>* labels);
60 
61  base::ObjectSubType GetObjectSubType(int label);
62 
63  // reference pointer of lidar frame
64  LidarFrame* lidar_frame_ref_ = nullptr;
65  std::shared_ptr<base::AttributePointCloud<base::PointF>> original_cloud_;
66  std::shared_ptr<base::AttributePointCloud<base::PointD>>
67  original_world_cloud_;
68 
69  // PointPillars
70  std::unique_ptr<PointPillars> point_pillars_ptr_;
71  std::deque<base::PointDCloudPtr> prev_world_clouds_;
72  base::PointFCloudPtr cur_cloud_ptr_;
73 
74  // point cloud range
75  float x_min_;
76  float x_max_;
77  float y_min_;
78  float y_max_;
79  float z_min_;
80  float z_max_;
81 
82  // time statistics
83  double downsample_time_ = 0.0;
84  double fuse_time_ = 0.0;
85  double shuffle_time_ = 0.0;
86  double cloud_to_array_time_ = 0.0;
87  double inference_time_ = 0.0;
88  double collect_time_ = 0.0;
89 }; // class MaskPillarsDetection
90 
91 } // namespace lidar
92 } // namespace perception
93 } // namespace apollo
Definition: mask_pillars_detection.h:36
bool Init(const LidarDetectorInitOptions &options=LidarDetectorInitOptions()) override
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_lidar_detector.h:34
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:482
Definition: base_lidar_detector.h:28
Definition: base_lidar_detector.h:32
bool Detect(const LidarDetectorOptions &options, LidarFrame *frame) override
Algorithm for PointPillars.
std::string Name() const override
Definition: mask_pillars_detection.h:46
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
ObjectSubType
Definition: object_types.h:63