@@ -209,12 +209,12 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::cameraInfoCallback(
209
209
{
210
210
// create the CameraProjection when the camera info arrives for the first time
211
211
// 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>(
215
215
*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 ();
218
218
}
219
219
}
220
220
@@ -252,8 +252,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::exportProcess()
252
252
}
253
253
254
254
// 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 ;
257
257
}
258
258
cached_det3d_msg_ptr_ = nullptr ;
259
259
}
@@ -296,16 +296,16 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
296
296
int64_t timestamp_nsec =
297
297
(*output_msg).header .stamp .sec * static_cast <int64_t >(1e9 ) + (*output_msg).header .stamp .nanosec ;
298
298
// 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 ;
301
301
302
302
// check camera info
303
- if (det_2d .camera_projector_ptr == nullptr ) {
303
+ if (det2d .camera_projector_ptr == nullptr ) {
304
304
RCLCPP_WARN_THROTTLE (
305
305
this ->get_logger (), *this ->get_clock (), 5000 , " no camera info. id is %zu" , roi_i);
306
306
continue ;
307
307
}
308
- auto & roi_msgs = det_2d .cached_det2d_msgs ;
308
+ auto & roi_msgs = det2d .cached_det2d_msgs ;
309
309
310
310
// check if the roi is collected
311
311
if (roi_msgs.size () == 0 ) continue ;
@@ -315,7 +315,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
315
315
int64_t matched_stamp = -1 ;
316
316
std::list<int64_t > outdate_stamps;
317
317
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 );
319
319
int64_t interval = abs (static_cast <int64_t >(roi_stamp) - new_stamp);
320
320
321
321
if (interval <= min_interval && interval <= match_threshold_ms_ * static_cast <int64_t >(1e6 )) {
@@ -339,7 +339,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
339
339
340
340
fuseOnSingleImage (*det3d_msg, roi_i, *(roi_msgs[matched_stamp]), *output_msg);
341
341
roi_msgs.erase (matched_stamp);
342
- det_2d .is_fused = true ;
342
+ det2d .is_fused = true ;
343
343
344
344
// add timestamp interval for debug
345
345
if (debug_publisher_) {
@@ -348,7 +348,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
348
348
" debug/roi" + std::to_string (roi_i) + " /timestamp_interval_ms" , timestamp_interval_ms);
349
349
debug_publisher_->publish <tier4_debug_msgs::msg::Float64Stamped>(
350
350
" 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 );
352
352
}
353
353
}
354
354
}
@@ -374,24 +374,24 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
374
374
375
375
stop_watch_ptr_->toc (" processing_time" , true );
376
376
377
- auto & det_2d = det2d_list_.at (roi_i);
377
+ auto & det2d = det2d_list_.at (roi_i);
378
378
379
379
int64_t timestamp_nsec =
380
380
(*det2d_msg).header .stamp .sec * static_cast <int64_t >(1e9 ) + (*det2d_msg).header .stamp .nanosec ;
381
381
382
382
// if cached Msg exist, try to match
383
383
if (cached_det3d_msg_ptr_ != nullptr ) {
384
384
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 );
386
386
int64_t interval = abs (timestamp_nsec - new_stamp);
387
387
388
388
// 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 ) {
390
390
// check camera info
391
- if (det_2d .camera_projector_ptr == nullptr ) {
391
+ if (det2d .camera_projector_ptr == nullptr ) {
392
392
RCLCPP_WARN_THROTTLE (
393
393
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;
395
395
return ;
396
396
}
397
397
@@ -400,15 +400,15 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
400
400
}
401
401
// PROCESS: fuse the main message with the roi message
402
402
fuseOnSingleImage (*(cached_det3d_msg_ptr_), roi_i, *det2d_msg, *(cached_det3d_msg_ptr_));
403
- det_2d .is_fused = true ;
403
+ det2d .is_fused = true ;
404
404
405
405
if (debug_publisher_) {
406
406
double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6 ;
407
407
debug_publisher_->publish <tier4_debug_msgs::msg::Float64Stamped>(
408
408
" debug/roi" + std::to_string (roi_i) + " /timestamp_interval_ms" , timestamp_interval_ms);
409
409
debug_publisher_->publish <tier4_debug_msgs::msg::Float64Stamped>(
410
410
" 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 );
412
412
}
413
413
414
414
// PROCESS: if all camera fused, postprocess and publish the main message
@@ -421,7 +421,7 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
421
421
}
422
422
}
423
423
// 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;
425
425
}
426
426
427
427
template <class TargetMsg3D , class Obj , class Msg2D >
@@ -447,8 +447,8 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::timer_callback()
447
447
}
448
448
449
449
// 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 ;
452
452
}
453
453
cached_det3d_msg_ptr_ = nullptr ;
454
454
0 commit comments