Apollo 10.0
自动驾驶开放平台
radar4d_detection_component.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 <memory>
19#include <string>
20#include <vector>
21
22#include "modules/common_msgs/localization_msgs/localization.pb.h"
23#include "modules/perception/radar4d_detection/proto/radar4d_component_config.pb.h"
24
37
38namespace apollo {
39namespace perception {
40namespace radar4d {
41
44
46 cyber::Component<drivers::OculiiPointCloud> {
47 public:
49 : tf_child_frame_id_(""),
50 radar_forward_distance_(200.0),
51 odometry_channel_name_(""),
52 hdmap_input_(nullptr),
53 radar_preprocessor_(nullptr),
54 radar_perception_(nullptr) {}
56
57 bool Init() override;
58 bool Proc(const std::shared_ptr<drivers::OculiiPointCloud>& message) override;
59
60 private:
61 bool InitAlgorithmPlugin(const Radar4dDetectionConfig& config);
62 bool InternalProc(
63 const std::shared_ptr<const drivers::OculiiPointCloud>& in_message,
64 std::shared_ptr<onboard::SensorFrameMessage> out_message);
65 bool GetCarLocalizationSpeed(double timestamp,
66 Eigen::Vector3f* car_linear_speed,
67 Eigen::Vector3f* car_angular_speed);
68
70 const Radar4dDetectionComponent&) = delete;
72 const Radar4dDetectionComponent&) = delete;
73
74 private:
75 static std::atomic<uint32_t> seq_num_;
76
77 base::SensorInfo radar_info_;
78 std::string tf_child_frame_id_;
79 double radar_forward_distance_;
80 std::string odometry_channel_name_;
81
82 onboard::TransformWrapper radar2world_trans_;
83 onboard::TransformWrapper radar2novatel_trans_;
84 map::HDMapInput* hdmap_input_;
85 std::shared_ptr<BasePreprocessor> radar_preprocessor_;
86 std::shared_ptr<BaseRadarObstaclePerception> radar_perception_;
87 onboard::MsgBuffer<LocalizationEstimate> localization_subscriber_;
88 std::shared_ptr<apollo::cyber::Writer<onboard::SensorFrameMessage>> writer_;
89};
90
92
93} // namespace radar4d
94} // namespace perception
95} // namespace apollo
bool Proc(const std::shared_ptr< drivers::OculiiPointCloud > &message) override
#define CYBER_REGISTER_COMPONENT(name)
Definition component.h:656
class register implement
Definition arena_queue.h:37