Apollo  v5.5.0
Open source self driving car software
pointcloud_preprocessor.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 "modules/drivers/proto/pointcloud.pb.h"
23 
24 namespace apollo {
25 namespace perception {
26 namespace lidar {
27 
29  std::string sensor_name = "velodyne64";
30 };
31 
33  Eigen::Affine3d sensor2novatel_extrinsics;
34 };
35 
37  public:
38  PointCloudPreprocessor() = default;
39 
40  ~PointCloudPreprocessor() = default;
41 
42  bool Init(const PointCloudPreprocessorInitOptions& options =
44 
45  // @brief: preprocess point cloud
46  // @param [in]: options
47  // @param [in]: point cloud message
48  // @param [in/out]: frame
49  // cloud should be filled, required,
50  bool Preprocess(
51  const PointCloudPreprocessorOptions& options,
52  const std::shared_ptr<apollo::drivers::PointCloud const>& message,
53  LidarFrame* frame) const;
54 
55  // @brief: preprocess point cloud
56  // @param [in/out]: frame
57  // cloud should be filled, required,
58  bool Preprocess(const PointCloudPreprocessorOptions& options,
59  LidarFrame* frame) const;
60 
61  std::string Name() const { return "PointCloudPreprocessor"; }
62 
63  private:
64  bool TransformCloud(const base::PointFCloudPtr& local_cloud,
65  const Eigen::Affine3d& pose,
66  base::PointDCloudPtr world_cloud) const;
67  // params
68  bool filter_naninf_points_ = true;
69  bool filter_nearby_box_points_ = true;
70  float box_forward_x_ = 0.0f;
71  float box_backward_x_ = 0.0f;
72  float box_forward_y_ = 0.0f;
73  float box_backward_y_ = 0.0f;
74  bool filter_high_z_points_ = true;
75  float z_threshold_ = 5.0f;
76  static const float kPointInfThreshold;
77 }; // class PointCloudPreprocessor
78 
79 } // namespace lidar
80 } // namespace perception
81 } // namespace apollo
Definition: pointcloud_preprocessor.h:36
Definition: blob.h:72
Definition: pointcloud_preprocessor.h:32
Definition: pointcloud_preprocessor.h:28
Eigen::Affine3d sensor2novatel_extrinsics
Definition: pointcloud_preprocessor.h:33
std::string sensor_name
Definition: pointcloud_preprocessor.h:29
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:472
std::string Name() const
Definition: pointcloud_preprocessor.h:61
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:475