Apollo  6.0
Open source self driving car software
base_pointcloud_preprocessor.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 <string>
19 #include <memory>
20 
21 #include "cyber/common/macros.h"
23 #include "modules/drivers/proto/pointcloud.pb.h"
25 
26 namespace apollo {
27 namespace perception {
28 namespace lidar {
29 
31  std::string sensor_name = "velodyne64";
32 };
33 
36 
37  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39 
41  public:
42  BasePointCloudPreprocessor() = default;
43 
44  virtual ~BasePointCloudPreprocessor() = default;
45 
46  virtual bool Init(const PointCloudPreprocessorInitOptions& options =
48 
49  // @brief: preprocess point cloud
50  // @param [in]: options
51  // @param [in]: point cloud message
52  // @param [in/out]: frame
53  // cloud should be filled, required,
54  virtual bool Preprocess(
55  const PointCloudPreprocessorOptions& options,
56  const std::shared_ptr<apollo::drivers::PointCloud const>& message,
57  LidarFrame* frame) const = 0;
58 
59  // @brief: preprocess point cloud
60  // @param [in/out]: frame
61  // cloud should be filled, required,
62  virtual bool Preprocess(const PointCloudPreprocessorOptions& options,
63  LidarFrame* frame) const = 0;
64 
65  virtual std::string Name() const = 0;
66 
67  private:
69 }; // class BasePointCloudPreprocessor
70 
72 #define PERCEPTION_REGISTER_POINTCLOUDPREPROCESSOR(name) \
73  PERCEPTION_REGISTER_CLASS(BasePointCloudPreprocessor, name)
74 
75 } // namespace lidar
76 } // namespace perception
77 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_pointcloud_preprocessor.h:34
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition: macros.h:48
struct apollo::perception::lidar::PCLPointXYZIT EIGEN_ALIGN16
Definition: base_pointcloud_preprocessor.h:30
Eigen::Affine3d sensor2novatel_extrinsics
Definition: base_pointcloud_preprocessor.h:35
std::string sensor_name
Definition: base_pointcloud_preprocessor.h:31
bool Init(const char *binary_name)
PERCEPTION_REGISTER_REGISTERER(BaseOneShotTypeFusion)
Definition: lidar_frame.h:33
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
Definition: base_pointcloud_preprocessor.h:40