Skip to content

Commit cdcf8ca

Browse files
committed
feat: Refactor fusion_node.cpp for improved code organization and readability
1 parent fced520 commit cdcf8ca

File tree

1 file changed

+24
-24
lines changed

1 file changed

+24
-24
lines changed

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

+24-24
Original file line numberDiff line numberDiff line change
@@ -209,12 +209,12 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::cameraInfoCallback(
209209
{
210210
// create the CameraProjection when the camera info arrives for the first time
211211
// assuming the camera info does not change while the node is running
212-
auto & det_2d = det2d_list_.at(camera_id);
213-
if (!det_2d.camera_projector_ptr && checkCameraInfo(*input_camera_info_msg)) {
214-
det_2d.camera_projector_ptr = std::make_unique<CameraProjection>(
212+
auto & det2d = det2d_list_.at(camera_id);
213+
if (!det2d.camera_projector_ptr && checkCameraInfo(*input_camera_info_msg)) {
214+
det2d.camera_projector_ptr = std::make_unique<CameraProjection>(
215215
*input_camera_info_msg, approx_grid_cell_w_size_, approx_grid_cell_h_size_,
216-
det_2d.project_to_unrectified_image, det_2d.approximate_camera_projection);
217-
det_2d.camera_projector_ptr->initialize();
216+
det2d.project_to_unrectified_image, det2d.approximate_camera_projection);
217+
det2d.camera_projector_ptr->initialize();
218218
}
219219
}
220220

@@ -252,8 +252,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::exportProcess()
252252
}
253253

254254
// reset flags
255-
for (auto & det_2d : det2d_list_) {
256-
det_2d.is_fused = false;
255+
for (auto & det2d : det2d_list_) {
256+
det2d.is_fused = false;
257257
}
258258
cached_det3d_msg_ptr_ = nullptr;
259259
}
@@ -296,16 +296,16 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
296296
int64_t timestamp_nsec =
297297
(*output_msg).header.stamp.sec * static_cast<int64_t>(1e9) + (*output_msg).header.stamp.nanosec;
298298
// for loop for each roi
299-
for (auto & det_2d : det2d_list_) {
300-
const auto roi_i = det_2d.id;
299+
for (auto & det2d : det2d_list_) {
300+
const auto roi_i = det2d.id;
301301

302302
// check camera info
303-
if (det_2d.camera_projector_ptr == nullptr) {
303+
if (det2d.camera_projector_ptr == nullptr) {
304304
RCLCPP_WARN_THROTTLE(
305305
this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i);
306306
continue;
307307
}
308-
auto & roi_msgs = det_2d.cached_det2d_msgs;
308+
auto & roi_msgs = det2d.cached_det2d_msgs;
309309

310310
// check if the roi is collected
311311
if (roi_msgs.size() == 0) continue;
@@ -315,7 +315,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
315315
int64_t matched_stamp = -1;
316316
std::list<int64_t> outdate_stamps;
317317
for (const auto & [roi_stamp, value] : roi_msgs) {
318-
int64_t new_stamp = timestamp_nsec + det_2d.input_offset_ms * static_cast<int64_t>(1e6);
318+
int64_t new_stamp = timestamp_nsec + det2d.input_offset_ms * static_cast<int64_t>(1e6);
319319
int64_t interval = abs(static_cast<int64_t>(roi_stamp) - new_stamp);
320320

321321
if (interval <= min_interval && interval <= match_threshold_ms_ * static_cast<int64_t>(1e6)) {
@@ -339,7 +339,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
339339

340340
fuseOnSingleImage(*det3d_msg, roi_i, *(roi_msgs[matched_stamp]), *output_msg);
341341
roi_msgs.erase(matched_stamp);
342-
det_2d.is_fused = true;
342+
det2d.is_fused = true;
343343

344344
// add timestamp interval for debug
345345
if (debug_publisher_) {
@@ -348,7 +348,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
348348
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms);
349349
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
350350
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms",
351-
timestamp_interval_ms - det_2d.input_offset_ms);
351+
timestamp_interval_ms - det2d.input_offset_ms);
352352
}
353353
}
354354
}
@@ -374,24 +374,24 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
374374

375375
stop_watch_ptr_->toc("processing_time", true);
376376

377-
auto & det_2d = det2d_list_.at(roi_i);
377+
auto & det2d = det2d_list_.at(roi_i);
378378

379379
int64_t timestamp_nsec =
380380
(*det2d_msg).header.stamp.sec * static_cast<int64_t>(1e9) + (*det2d_msg).header.stamp.nanosec;
381381

382382
// if cached Msg exist, try to match
383383
if (cached_det3d_msg_ptr_ != nullptr) {
384384
int64_t new_stamp =
385-
cached_det3d_msg_timestamp_ + det_2d.input_offset_ms * static_cast<int64_t>(1e6);
385+
cached_det3d_msg_timestamp_ + det2d.input_offset_ms * static_cast<int64_t>(1e6);
386386
int64_t interval = abs(timestamp_nsec - new_stamp);
387387

388388
// PROCESS: if matched, fuse the main message with the roi message
389-
if (interval < match_threshold_ms_ * static_cast<int64_t>(1e6) && det_2d.is_fused == false) {
389+
if (interval < match_threshold_ms_ * static_cast<int64_t>(1e6) && det2d.is_fused == false) {
390390
// check camera info
391-
if (det_2d.camera_projector_ptr == nullptr) {
391+
if (det2d.camera_projector_ptr == nullptr) {
392392
RCLCPP_WARN_THROTTLE(
393393
this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i);
394-
det_2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg;
394+
det2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg;
395395
return;
396396
}
397397

@@ -400,15 +400,15 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
400400
}
401401
// PROCESS: fuse the main message with the roi message
402402
fuseOnSingleImage(*(cached_det3d_msg_ptr_), roi_i, *det2d_msg, *(cached_det3d_msg_ptr_));
403-
det_2d.is_fused = true;
403+
det2d.is_fused = true;
404404

405405
if (debug_publisher_) {
406406
double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6;
407407
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
408408
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms);
409409
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
410410
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms",
411-
timestamp_interval_ms - det_2d.input_offset_ms);
411+
timestamp_interval_ms - det2d.input_offset_ms);
412412
}
413413

414414
// PROCESS: if all camera fused, postprocess and publish the main message
@@ -421,7 +421,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
421421
}
422422
}
423423
// store roi msg if not matched
424-
det_2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg;
424+
det2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg;
425425
}
426426

427427
template <class TargetMsg3D, class Obj, class Msg2D>
@@ -447,8 +447,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::timer_callback()
447447
}
448448

449449
// reset flags whether the message is fused or not
450-
for (auto & det_2d : det2d_list_) {
451-
det_2d.is_fused = false;
450+
for (auto & det2d : det2d_list_) {
451+
det2d.is_fused = false;
452452
}
453453
cached_det3d_msg_ptr_ = nullptr;
454454

0 commit comments

Comments
 (0)