21
21
22
22
#include < iterator>
23
23
24
+ #include < rclcpp/logging.hpp>
25
+
26
+
24
27
using Label = autoware_perception_msgs::msg::ObjectClassification;
25
28
26
29
TrackerProcessor::TrackerProcessor (
@@ -47,13 +50,13 @@ void TrackerProcessor::predict(const rclcpp::Time & time)
47
50
}
48
51
49
52
void TrackerProcessor::update (
50
- // Add at the beginning of the function
51
- std::string debug_message = " " ;
52
-
53
53
const autoware_perception_msgs::msg::DetectedObjects & detected_objects,
54
54
const geometry_msgs::msg::Transform & self_transform,
55
55
const std::unordered_map<int , int > & direct_assignment, const uint & channel_index)
56
56
{
57
+ // Add at the beginning of the function
58
+ std::string debug_message = " " ;
59
+
57
60
int tracker_idx = 0 ;
58
61
const auto & time = detected_objects.header .stamp ;
59
62
for (auto tracker_itr = list_tracker_.begin (); tracker_itr != list_tracker_.end ();
@@ -65,11 +68,10 @@ void TrackerProcessor::update(
65
68
->updateWithMeasurement (associated_object, time , self_transform, channel_index);
66
69
67
70
char buf[120 ];
68
- snprintf (buf, sizeof (buf), " track meas update idx[%d], x[%.3f], y[%.3f], t[%.3f], cls[%d]\n " ,
71
+ snprintf (buf, sizeof (buf), " track meas update idx[%d], x[%.3f], y[%.3f], cls[%d]\n " ,
69
72
tracker_idx,
70
73
associated_object.kinematics .pose_with_covariance .pose .position .x ,
71
74
associated_object.kinematics .pose_with_covariance .pose .position .y ,
72
- measurement_time.seconds (),
73
75
associated_object.classification .at (0 ).label );
74
76
debug_message += buf;
75
77
@@ -78,19 +80,18 @@ void TrackerProcessor::update(
78
80
(*(tracker_itr))->updateWithoutMeasurement (time );
79
81
80
82
char buf[120 ];
81
- snprintf (buf, sizeof (buf), " track no meas update idx[%d], x[%.3f], y[%.3f], t[%.3f], cls[%d]\n " ,
83
+ snprintf (buf, sizeof (buf), " track no meas update idx[%d], x[%.3f], y[%.3f], cls[%d]\n " ,
82
84
tracker_idx,
83
85
associated_object.kinematics .pose_with_covariance .pose .position .x ,
84
86
associated_object.kinematics .pose_with_covariance .pose .position .y ,
85
- measurement_time.seconds (),
86
87
associated_object.classification .at (0 ).label );
87
88
debug_message += buf;
88
89
89
90
}
90
91
}
91
92
// Add at the end of the function, before return
92
93
if (!debug_message.empty ()) {
93
- RCLCPP_INFO (get_logger (), " \n object updates:\n %s" , debug_message.c_str ());
94
+ RCLCPP_INFO (rclcpp:: get_logger (" multi_object_tracker " ), " \n object updates:\n %s" , debug_message.c_str ());
94
95
}
95
96
}
96
97
@@ -109,7 +110,7 @@ void TrackerProcessor::spawn(
109
110
createNewTracker (new_object, time , self_transform, channel_index);
110
111
if (tracker) {
111
112
list_tracker_.push_back (tracker);
112
- RCLCPP_INFO (get_logger (), " New tracker" );
113
+ RCLCPP_INFO (rclcpp:: get_logger (" multi_object_tracker " ), " New tracker [%ld] " , i );
113
114
}
114
115
}
115
116
}
@@ -240,7 +241,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
240
241
sorted_list_tracker.erase (sorted_list_tracker.begin () + j);
241
242
--j;
242
243
243
- RCLCPP_INFO (get_logger (), " Erase tracker [%d ] -> [%d ] " , i, j);
244
+ RCLCPP_INFO (rclcpp:: get_logger (" multi_object_tracker " ), " Erase tracker [%ld ] -> [%ld ] " , i, j);
244
245
}
245
246
}
246
247
}
0 commit comments