Apollo  v5.5.0
Open source self driving car software
lidar_obstacle_segmentation.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 
21 #include "Eigen/Dense"
22 
30 
31 namespace apollo {
32 namespace perception {
33 namespace lidar {
34 
36  std::string sensor_name = "velodyne64";
37  bool enable_hdmap_input = true;
38 };
39 
41  std::string sensor_name;
42  Eigen::Affine3d sensor2novatel_extrinsics;
43 };
44 
46  public:
47  LidarObstacleSegmentation() = default;
48  ~LidarObstacleSegmentation() = default;
49 
50  bool Init(const LidarObstacleSegmentationInitOptions& options =
52 
53  LidarProcessResult Process(
54  const LidarObstacleSegmentationOptions& options,
55  const std::shared_ptr<apollo::drivers::PointCloud const>& message,
56  LidarFrame* frame);
57 
59  LidarFrame* frame);
60 
61  std::string Name() const { return "LidarObstacleSegmentation"; }
62 
63  private:
64  LidarProcessResult ProcessCommon(
65  const LidarObstacleSegmentationOptions& options, LidarFrame* frame);
66 
67  private:
68  PointCloudPreprocessor cloud_preprocessor_;
69  MapManager map_manager_;
70  std::unique_ptr<BaseSegmentation> segmentor_;
71  ObjectBuilder builder_;
72  ObjectFilterBank filter_bank_;
73  // params
74  std::string segmentor_name_;
75  bool use_map_manager_ = true;
76  bool use_object_filter_bank_ = true;
77 }; // class LidarObstacleSegmentation
78 
79 } // namespace lidar
80 } // namespace perception
81 } // namespace apollo
Definition: pointcloud_preprocessor.h:36
Definition: blob.h:72
std::string Name() const
Definition: lidar_obstacle_segmentation.h:61
Definition: object_builder.h:38
std::string sensor_name
Definition: lidar_obstacle_segmentation.h:41
Definition: lidar_obstacle_segmentation.h:35
Definition: lidar_frame.h:33
Definition: map_manager.h:34
Definition: lidar_obstacle_segmentation.h:40
Definition: object_filter_bank.h:28
Definition: lidar_error_code.h:36
Definition: lidar_obstacle_segmentation.h:45
Eigen::Affine3d sensor2novatel_extrinsics
Definition: lidar_obstacle_segmentation.h:42
std::string sensor_name
Definition: lidar_obstacle_segmentation.h:36
bool enable_hdmap_input
Definition: lidar_obstacle_segmentation.h:37