Apollo 11.0
自动驾驶开放平台
base_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
21#include "modules/common_msgs/sensor_msgs/oculii_radar.pb.h"
24
25#include "cyber/common/macros.h"
29
30namespace apollo {
31namespace perception {
32namespace radar4d {
33
35 // reserved
36};
37
39 Eigen::Matrix4d* radar2world_pose = nullptr;
40 Eigen::Matrix4d* radar2novatel_trans = nullptr;
41 Eigen::Vector3f car_linear_speed = Eigen::Vector3f::Zero();
42 Eigen::Vector3f car_angular_speed = Eigen::Vector3f::Zero();
43};
44
46 public:
51 BasePreprocessor() = default;
52 virtual ~BasePreprocessor() = default;
53
61 virtual bool Init(const PreprocessorInitOptions& options) = 0;
62
72 virtual bool Preprocess(
73 const std::shared_ptr<apollo::drivers::OculiiPointCloud const>& message,
74 const PreprocessorOptions& options,
75 RadarFrame* frame) = 0;
76
82 virtual std::string Name() const = 0;
83
84 private:
86};
87
89#define PERCEPTION_REGISTER_PREPROCESSOR(name) \
90 PERCEPTION_REGISTER_CLASS(BasePreprocessor, name)
91
92} // namespace radar4d
93} // namespace perception
94} // namespace apollo
virtual bool Preprocess(const std::shared_ptr< apollo::drivers::OculiiPointCloud const > &message, const PreprocessorOptions &options, RadarFrame *frame)=0
Process radar point cloud.
BasePreprocessor()=default
Construct a new Base Preprocessor object
virtual bool Init(const PreprocessorInitOptions &options)=0
Init base preprocessor config
virtual std::string Name() const =0
The name of the radar base Preprocessor
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition macros.h:48
class register implement
Definition arena_queue.h:37
#define PERCEPTION_REGISTER_REGISTERER(base_class)
Definition registerer.h:92