29std::atomic<uint32_t> Radar4dDetectionComponent::seq_num_{0};
37 AINFO <<
"Radar4d Detection Component Config: " <<
38 comp_config.DebugString();
45 if (!algorithm::SensorManager::Instance()->GetSensorInfo(
47 AERROR <<
"Failed to get sensor info, sensor name: "
57 ACHECK(InitAlgorithmPlugin(comp_config))
58 <<
"Failed to init algorithm plugin.";
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());
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>();
76 if (!InternalProc(message, out_message)) {
79 writer_->Write(out_message);
83bool Radar4dDetectionComponent::InitAlgorithmPlugin(
86 if (onboard::FLAGS_obs_enable_hdmap_input) {
87 hdmap_input_ = map::HDMapInput::Instance();
88 ACHECK(hdmap_input_->
Init()) <<
"Failed to init hdmap input.";
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.";
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.";
118bool Radar4dDetectionComponent::InternalProc(
119 const std::shared_ptr<const drivers::OculiiPointCloud>& in_message,
120 std::shared_ptr<onboard::SensorFrameMessage> out_message) {
124 uint32_t seq_num = seq_num_.fetch_add(1);
125 double timestamp = in_message->measurement_time();
126 out_message->timestamp_ = timestamp;
130 std::shared_ptr<RadarFrame> radar_frame_(
new RadarFrame);
132 radar_frame_->cloud = base::RadarPointFCloudPool::Instance().Get();
133 radar_frame_->timestamp = timestamp;
134 radar_frame_->sensor_info = radar_info_;
137 PreprocessorOptions preprocessor_options;
138 RadarPerceptionOptions options;
139 options.sensor_name = radar_info_.
name;
142 Eigen::Affine3d radar_trans;
143 Eigen::Affine3d novatel2world_trans;
145 timestamp, &radar_trans, &novatel2world_trans)) {
147 AERROR <<
"Failed to get pose at time: " << timestamp;
150 Eigen::Affine3d radar2novatel_trans;
151 if (!radar2novatel_trans_.
GetTrans(timestamp, &radar2novatel_trans,
"novatel",
152 tf_child_frame_id_)) {
154 AERROR <<
"Failed to get radar2novatel trans at time: " << timestamp;
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;
167 if (!GetCarLocalizationSpeed(timestamp,
168 &(preprocessor_options.car_linear_speed),
169 &(preprocessor_options.car_angular_speed))) {
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;
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) {
187 options.roi_filter_options.roi);
192 radar_preprocessor_->Preprocess(in_message, preprocessor_options,
197 std::vector<base::ObjectPtr> radar_objects;
198 if (!radar_perception_->Perceive(radar_frame_.get(), options,
200 out_message->error_code_ =
202 AERROR <<
"RadarDetector Proc failed.";
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;
216 radar_info_.
name,
"radar_perception");
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";
227 (*car_linear_speed) = Eigen::Vector3f::Zero();
229 if (car_angular_speed ==
nullptr) {
230 AERROR <<
"car_angular_speed is not available";
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.";
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());
a singleton clock that can be used to get the current timestamp.
static double NowInSeconds()
gets the current time in second.
bool GetProtoConfig(T *config) const
std::shared_ptr< Node > node_
static ConcurrentObjectPool & Instance()
std::shared_ptr< ObjectType > Get() override
bool Proc(const std::shared_ptr< drivers::OculiiPointCloud > &message) override
@ PERCEPTION_ERROR_PROCESS
@ LONG_RANGE_RADAR_DETECTION
#define PERF_BLOCK_END_WITH_INDICATOR(indicator, msg)
#define PERF_FUNCTION_WITH_INDICATOR(indicator)
#define PERF_BLOCK_START()
optional string config_path
optional string tf_child_frame_id
optional perception::PluginParam perception_param
optional string odometry_channel_name
optional double radar_forward_distance
optional string output_channel_name
optional string radar_name
optional perception::PluginParam preprocessor_param