Apollo 11.0
自动驾驶开放平台
radar_preprocessor.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2023 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#include <unordered_map>
21
22#include "cyber/common/macros.h"
24
25namespace apollo {
26namespace perception {
27namespace radar4d {
28
30 public:
31 RadarPreprocessor() : BasePreprocessor(), rcs_offset_(0.0) {}
32 virtual ~RadarPreprocessor() {}
33
41 bool Init(const PreprocessorInitOptions& options) override;
42
52 bool Preprocess(
53 const std::shared_ptr<apollo::drivers::OculiiPointCloud const>& message,
54 const PreprocessorOptions& options,
55 RadarFrame* frame) override;
56
62 std::string Name() const override { return "RadarPreprocessor"; }
63
64 private:
65 bool TransformCloud(const base::RadarPointFCloudPtr& local_cloud,
66 const Eigen::Affine3d& pose,
67 base::RadarPointDCloudPtr world_cloud) const;
68
69 float CalCompensatedVelocity(
70 const base::RadarPointF& point,
71 const PreprocessorOptions& options);
72
73 float rcs_offset_ = 0.0f;
74 bool filter_naninf_points_ = true;
75 bool filter_high_z_points_ = true;
76 float z_threshold_ = 5.0f;
77 static const float kPointInfThreshold;
78
79 static int current_idx_;
80 static std::unordered_map<int, int> local2global_;
81
83};
84
85} // namespace radar4d
86} // namespace perception
87} // namespace apollo
bool Init(const PreprocessorInitOptions &options) override
Init RadarPreprocessor config
bool Preprocess(const std::shared_ptr< apollo::drivers::OculiiPointCloud const > &message, const PreprocessorOptions &options, RadarFrame *frame) override
Process radar point cloud.
std::string Name() const override
The name of the RadarPreprocessor
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition macros.h:48
std::shared_ptr< RadarPointFCloud > RadarPointFCloudPtr
std::shared_ptr< RadarPointDCloud > RadarPointDCloudPtr
class register implement
Definition arena_queue.h:37