Apollo  6.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 <string>
19 #include <memory>
20 
22 
23 namespace apollo {
24 namespace perception {
25 namespace lidar {
26 
28  public:
30 
31  virtual ~PointCloudPreprocessor() = default;
32 
33  bool Init(const PointCloudPreprocessorInitOptions& options =
35 
36  bool Preprocess(
37  const PointCloudPreprocessorOptions& options,
38  const std::shared_ptr<apollo::drivers::PointCloud const>& message,
39  LidarFrame* frame) const override;
40 
41  bool Preprocess(const PointCloudPreprocessorOptions& options,
42  LidarFrame* frame) const override;
43 
44  std::string Name() const override { return "PointCloudPreprocessor"; }
45 
46  private:
47  bool TransformCloud(const base::PointFCloudPtr& local_cloud,
48  const Eigen::Affine3d& pose,
49  base::PointDCloudPtr world_cloud) const;
50  // params
51  bool filter_naninf_points_ = true;
52  bool filter_nearby_box_points_ = true;
53  float box_forward_x_ = 0.0f;
54  float box_backward_x_ = 0.0f;
55  float box_forward_y_ = 0.0f;
56  float box_backward_y_ = 0.0f;
57  bool filter_high_z_points_ = true;
58  float z_threshold_ = 5.0f;
59  static const float kPointInfThreshold;
60 }; // class PointCloudPreprocessor
61 
62 } // namespace lidar
63 } // namespace perception
64 } // namespace apollo
Definition: pointcloud_preprocessor.h:27
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
bool Init(const PointCloudPreprocessorInitOptions &options=PointCloudPreprocessorInitOptions()) override
Definition: base_pointcloud_preprocessor.h:30
bool Preprocess(const PointCloudPreprocessorOptions &options, const std::shared_ptr< apollo::drivers::PointCloud const > &message, LidarFrame *frame) const override
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:482
std::string Name() const override
Definition: pointcloud_preprocessor.h:44
PointCloudPreprocessor()
Definition: pointcloud_preprocessor.h:29
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:485
Definition: base_pointcloud_preprocessor.h:40