Apollo 10.0
自动驾驶开放平台
radar4d_detection_component.cc
浏览该文件的文档.
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 *****************************************************************************/
17
18#include "cyber/time/clock.h"
22
24
25namespace apollo {
26namespace perception {
27namespace radar4d {
28
29std::atomic<uint32_t> Radar4dDetectionComponent::seq_num_{0};
30
32 // To load component configs
33 Radar4dDetectionConfig comp_config;
34 if (!GetProtoConfig(&comp_config)) {
35 return false;
36 }
37 AINFO << "Radar4d Detection Component Config: " <<
38 comp_config.DebugString();
39
40 tf_child_frame_id_ = comp_config.tf_child_frame_id();
41 radar_forward_distance_ = comp_config.radar_forward_distance();
42 odometry_channel_name_ = comp_config.odometry_channel_name();
43
44 // Load sensor info
45 if (!algorithm::SensorManager::Instance()->GetSensorInfo(
46 comp_config.radar_name(), &radar_info_)) {
47 AERROR << "Failed to get sensor info, sensor name: "
48 << comp_config.radar_name();
49 return false;
50 }
51
52 // Create writer
53 writer_ = node_->CreateWriter<onboard::SensorFrameMessage>(
54 comp_config.output_channel_name());
55
56 // Init algorithm plugin
57 ACHECK(InitAlgorithmPlugin(comp_config))
58 << "Failed to init algorithm plugin.";
59
60 // Init localization config
61 radar2world_trans_.Init(tf_child_frame_id_);
62 radar2novatel_trans_.Init(tf_child_frame_id_);
63 localization_subscriber_.Init(
64 odometry_channel_name_,
65 odometry_channel_name_ + '_' + comp_config.radar_name());
66 return true;
67}
68
70 const std::shared_ptr<drivers::OculiiPointCloud>& message) {
71 AINFO << "Enter radar preprocess, message timestamp: "
72 << message->header().timestamp_sec() << " current timestamp "
74 auto out_message = std::make_shared<onboard::SensorFrameMessage>();
75
76 if (!InternalProc(message, out_message)) {
77 return false;
78 }
79 writer_->Write(out_message);
80 return true;
81}
82
83bool Radar4dDetectionComponent::InitAlgorithmPlugin(
84 const Radar4dDetectionConfig& config) {
85 // Hdmap input
86 if (onboard::FLAGS_obs_enable_hdmap_input) {
87 hdmap_input_ = map::HDMapInput::Instance();
88 ACHECK(hdmap_input_->Init()) << "Failed to init hdmap input.";
89 }
90
91 // Init preprocessor plugin
92 auto preprocessor_param = config.preprocessor_param();
93 PreprocessorInitOptions preprocessor_init_options;
94 preprocessor_init_options.config_path = preprocessor_param.config_path();
95 preprocessor_init_options.config_file = preprocessor_param.config_file();
96 BasePreprocessor* radar_preprocessor =
97 BasePreprocessorRegisterer::GetInstanceByName(preprocessor_param.name());
98 CHECK_NOTNULL(radar_preprocessor);
99 radar_preprocessor_.reset(radar_preprocessor);
100 ACHECK(radar_preprocessor_->Init(preprocessor_init_options))
101 << "Failed to init radar preprocessor.";
102
103 // Init perception plugin
104 auto perception_param = config.perception_param();
105 PerceptionInitOptions perception_init_options;
106 perception_init_options.config_path = perception_param.config_path();
107 perception_init_options.config_file = perception_param.config_file();
108 BaseRadarObstaclePerception* radar_perception =
109 BaseRadarObstaclePerceptionRegisterer::GetInstanceByName(
110 perception_param.name());
111 CHECK_NOTNULL(radar_perception);
112 radar_perception_.reset(radar_perception);
113 ACHECK(radar_perception_->Init(perception_init_options))
114 << "Failed to init radar perception.";
115 return true;
116}
117
118bool Radar4dDetectionComponent::InternalProc(
119 const std::shared_ptr<const drivers::OculiiPointCloud>& in_message,
120 std::shared_ptr<onboard::SensorFrameMessage> out_message) {
121
123
124 uint32_t seq_num = seq_num_.fetch_add(1);
125 double timestamp = in_message->measurement_time();
126 out_message->timestamp_ = timestamp;
128
129 // Init radar frame
130 std::shared_ptr<RadarFrame> radar_frame_(new RadarFrame);
131 radar_frame_ = radar4d::RadarFramePool::Instance().Get();
132 radar_frame_->cloud = base::RadarPointFCloudPool::Instance().Get();
133 radar_frame_->timestamp = timestamp;
134 radar_frame_->sensor_info = radar_info_;
135
136 // Init radar perception options
137 PreprocessorOptions preprocessor_options;
138 RadarPerceptionOptions options;
139 options.sensor_name = radar_info_.name;
140
141 // Init detector_options and preprocessor_options
142 Eigen::Affine3d radar_trans;
143 Eigen::Affine3d novatel2world_trans;
144 if (!radar2world_trans_.GetSensor2worldTrans(
145 timestamp, &radar_trans, &novatel2world_trans)) {
146 out_message->error_code_ = apollo::common::ErrorCode::PERCEPTION_ERROR_TF;
147 AERROR << "Failed to get pose at time: " << timestamp;
148 return true;
149 }
150 Eigen::Affine3d radar2novatel_trans;
151 if (!radar2novatel_trans_.GetTrans(timestamp, &radar2novatel_trans, "novatel",
152 tf_child_frame_id_)) {
153 out_message->error_code_ = apollo::common::ErrorCode::PERCEPTION_ERROR_TF;
154 AERROR << "Failed to get radar2novatel trans at time: " << timestamp;
155 return true;
156 }
157 radar_frame_->radar2world_pose = radar_trans;
158 radar_frame_->novatel2world_pose = novatel2world_trans;
159 Eigen::Matrix4d radar2world_pose_m = radar_trans.matrix();
160 options.detector_options.radar2world_pose = &radar2world_pose_m;
161 preprocessor_options.radar2world_pose = &radar2world_pose_m;
162 Eigen::Matrix4d radar2novatel_trans_m = radar2novatel_trans.matrix();
163 options.detector_options.radar2novatel_trans = &radar2novatel_trans_m;
164 preprocessor_options.radar2novatel_trans = &radar2novatel_trans_m;
165 PERF_BLOCK_END_WITH_INDICATOR(radar_info_.name, "GetSensor2worldTrans");
166
167 if (!GetCarLocalizationSpeed(timestamp,
168 &(preprocessor_options.car_linear_speed),
169 &(preprocessor_options.car_angular_speed))) {
170 AERROR << "Failed to call get_car_speed. [timestamp: " << timestamp;
171 // return false;
172 }
173 options.detector_options.car_linear_speed =
174 preprocessor_options.car_linear_speed;
175 options.detector_options.car_angular_speed =
176 preprocessor_options.car_angular_speed;
177 PERF_BLOCK_END_WITH_INDICATOR(radar_info_.name, "GetCarSpeed");
178
179 // Init roi_filter_options
180 base::PointD position;
181 position.x = radar_trans(0, 3);
182 position.y = radar_trans(1, 3);
183 position.z = radar_trans(2, 3);
184 options.roi_filter_options.roi.reset(new base::HdmapStruct());
185 if (onboard::FLAGS_obs_enable_hdmap_input) {
186 hdmap_input_->GetRoiHDMapStruct(position, radar_forward_distance_,
187 options.roi_filter_options.roi);
188 }
189 PERF_BLOCK_END_WITH_INDICATOR(radar_info_.name, "GetRoiHDMapStruct");
190
191 // Radar preprocess
192 radar_preprocessor_->Preprocess(in_message, preprocessor_options,
193 radar_frame_.get());
194 PERF_BLOCK_END_WITH_INDICATOR(radar_info_.name, "radar_preprocessor");
195
196 // Radar perception
197 std::vector<base::ObjectPtr> radar_objects;
198 if (!radar_perception_->Perceive(radar_frame_.get(), options,
199 &radar_objects)) {
200 out_message->error_code_ =
202 AERROR << "RadarDetector Proc failed.";
203 return true;
204 }
205 out_message->frame_.reset(new base::Frame());
206 out_message->frame_->sensor_info = radar_info_;
207 out_message->frame_->timestamp = timestamp;
208 out_message->frame_->sensor2world_pose = radar_trans;
209 out_message->frame_->objects = radar_objects;
210 out_message->seq_num_ = seq_num;
211 out_message->process_stage_ =
213 out_message->sensor_id_ = radar_info_.name;
214
216 radar_info_.name, "radar_perception");
217 return true;
218}
219
220bool Radar4dDetectionComponent::GetCarLocalizationSpeed(
221 double timestamp, Eigen::Vector3f* car_linear_speed,
222 Eigen::Vector3f* car_angular_speed) {
223 if (car_linear_speed == nullptr) {
224 AERROR << "car_linear_speed is not available";
225 return false;
226 }
227 (*car_linear_speed) = Eigen::Vector3f::Zero();
228
229 if (car_angular_speed == nullptr) {
230 AERROR << "car_angular_speed is not available";
231 return false;
232 }
233 (*car_angular_speed) = Eigen::Vector3f::Zero();
234 std::shared_ptr<LocalizationEstimate const> loct_ptr;
235 if (!localization_subscriber_.LookupNearest(timestamp, &loct_ptr)) {
236 AERROR << "Cannot get car speed.";
237 return false;
238 }
239 (*car_linear_speed)[0] =
240 static_cast<float>(loct_ptr->pose().linear_velocity().x());
241 (*car_linear_speed)[1] =
242 static_cast<float>(loct_ptr->pose().linear_velocity().y());
243 (*car_linear_speed)[2] =
244 static_cast<float>(loct_ptr->pose().linear_velocity().z());
245 (*car_angular_speed)[0] =
246 static_cast<float>(loct_ptr->pose().angular_velocity().x());
247 (*car_angular_speed)[1] =
248 static_cast<float>(loct_ptr->pose().angular_velocity().y());
249 (*car_angular_speed)[2] =
250 static_cast<float>(loct_ptr->pose().angular_velocity().z());
251
252 return true;
253}
254
255} // namespace radar4d
256} // namespace perception
257} // namespace apollo
Set the behavior of the
a singleton clock that can be used to get the current timestamp.
Definition clock.h:39
static double NowInSeconds()
gets the current time in second.
Definition clock.cc:56
bool GetProtoConfig(T *config) const
std::shared_ptr< Node > node_
std::shared_ptr< ObjectType > Get() override
bool GetRoiHDMapStruct(const base::PointD &pointd, const double distance, std::shared_ptr< base::HdmapStruct > hdmap_struct_prt)
bool GetTrans(double timestamp, Eigen::Affine3d *trans, const std::string &frame_id, const std::string &child_frame_id)
bool GetSensor2worldTrans(double timestamp, Eigen::Affine3d *sensor2world_trans, Eigen::Affine3d *novatel2world_trans=nullptr)
void Init(const std::string &sensor2novatel_tf2_child_frame_id)
bool Proc(const std::shared_ptr< drivers::OculiiPointCloud > &message) override
#define ACHECK(cond)
Definition log.h:80
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
Point< double > PointD
Definition point.h:57
class register implement
Definition arena_queue.h:37
#define PERF_BLOCK_END_WITH_INDICATOR(indicator, msg)
Definition perf_util.h:128
#define PERF_FUNCTION_WITH_INDICATOR(indicator)
Definition perf_util.h:125
#define PERF_BLOCK_START()
Definition perf_util.h:126