Apollo  6.0
Open source self driving car software
radar_detection_component.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 #include <vector>
21 
23 #include "modules/localization/proto/localization.pb.h"
29 #include "modules/perception/onboard/proto/radar_component_config.pb.h"
32 
33 namespace apollo {
34 namespace perception {
35 namespace onboard {
36 
37 using apollo::drivers::ContiRadar;
38 using apollo::localization::LocalizationEstimate;
39 
40 class RadarDetectionComponent : public cyber::Component<ContiRadar> {
41  public:
43  : seq_num_(0),
44  tf_child_frame_id_(""),
45  radar_forward_distance_(200.0),
46  preprocessor_method_(""),
47  perception_method_(""),
48  pipeline_name_(""),
49  odometry_channel_name_(""),
50  hdmap_input_(nullptr),
51  radar_preprocessor_(nullptr),
52  radar_perception_(nullptr) {}
53  ~RadarDetectionComponent() = default;
54 
55  bool Init() override;
56  bool Proc(const std::shared_ptr<ContiRadar>& message) override;
57 
58  private:
59  bool InitAlgorithmPlugin();
60  bool InternalProc(const std::shared_ptr<ContiRadar>& in_message,
61  std::shared_ptr<SensorFrameMessage> out_message);
62  bool GetCarLocalizationSpeed(double timestamp,
63  Eigen::Vector3f* car_linear_speed,
64  Eigen::Vector3f* car_angular_speed);
65 
67  RadarDetectionComponent& operator=(const RadarDetectionComponent&) = delete;
68 
69  private:
70  std::mutex _mutex;
71  uint32_t seq_num_;
72 
73  base::SensorInfo radar_info_;
74  std::string tf_child_frame_id_;
75  double radar_forward_distance_;
76  std::string preprocessor_method_;
77  std::string perception_method_;
78  std::string pipeline_name_;
79  std::string odometry_channel_name_;
80 
81  TransformWrapper radar2world_trans_;
82  TransformWrapper radar2novatel_trans_;
83  map::HDMapInput* hdmap_input_;
84  std::shared_ptr<radar::BasePreprocessor> radar_preprocessor_;
85  std::shared_ptr<radar::BaseRadarObstaclePerception> radar_perception_;
86  MsgBuffer<LocalizationEstimate> localization_subscriber_;
87  std::shared_ptr<apollo::cyber::Writer<SensorFrameMessage>> writer_;
88 };
89 
91 
92 } // namespace onboard
93 } // namespace perception
94 } // namespace apollo
Definition: radar_detection_component.h:40
Eigen::Vector3f Vector3f
Definition: base_map_fwd.h:29
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: transform_wrapper.h:62
RadarDetectionComponent()
Definition: radar_detection_component.h:42
Definition: hdmap_input.h:34
Definition: sensor_meta.h:57
bool Proc(const std::shared_ptr< ContiRadar > &message) override
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58
CYBER_REGISTER_COMPONENT(CameraObstacleDetectionComponent)