Apollo  6.0
Open source self driving car software
base_lidar_obstacle_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 <memory>
19 #include <string>
20 
21 #include "Eigen/Dense"
22 
23 #include "cyber/common/macros.h"
26 #include "modules/drivers/proto/pointcloud.pb.h"
28 
29 namespace apollo {
30 namespace perception {
31 namespace lidar {
32 
34  std::string sensor_name = "velodyne64";
35  bool enable_hdmap_input = true;
36 };
37 
39  std::string sensor_name;
41 
42  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 
46  public:
47  BaseLidarObstacleDetection() = default;
48  virtual ~BaseLidarObstacleDetection() = default;
49 
50  virtual bool Init(
51  const LidarObstacleDetectionInitOptions& options =
53 
54  virtual LidarProcessResult Process(
55  const LidarObstacleDetectionOptions& options,
56  const std::shared_ptr<apollo::drivers::PointCloud const>& message,
57  LidarFrame* frame) = 0;
58 
59  virtual LidarProcessResult Process(
60  const LidarObstacleDetectionOptions& options,
61  LidarFrame* frame) = 0;
62 
63  virtual std::string Name() const = 0;
64 
65  private:
67 }; // class BaseLidarObstacleDetection
68 
70 #define PERCEPTION_REGISTER_LIDAROBSTACLEDETECTION(name) \
71  PERCEPTION_REGISTER_CLASS(BaseLidarObstacleDetection, name)
72 
73 } // namespace lidar
74 } // namespace perception
75 } // namespace apollo
Definition: base_lidar_obstacle_detection.h:38
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool enable_hdmap_input
Definition: base_lidar_obstacle_detection.h:35
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition: macros.h:48
Eigen::Affine3d sensor2novatel_extrinsics
Definition: base_lidar_obstacle_detection.h:40
struct apollo::perception::lidar::PCLPointXYZIT EIGEN_ALIGN16
std::string sensor_name
Definition: base_lidar_obstacle_detection.h:34
bool Init(const char *binary_name)
std::string sensor_name
Definition: base_lidar_obstacle_detection.h:39
PERCEPTION_REGISTER_REGISTERER(BaseOneShotTypeFusion)
Definition: base_lidar_obstacle_detection.h:45
Definition: lidar_frame.h:33
Definition: lidar_error_code.h:36
Definition: base_lidar_obstacle_detection.h:33
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34