18
18
19
19
#include < memory>
20
20
21
- TrackerDebugger::TrackerDebugger (rclcpp::Node & node)
22
- : diagnostic_updater_(&node),
23
- node_(node),
24
- last_input_stamp_(node.now()),
25
- stamp_process_start_(node.now()),
26
- stamp_publish_output_(node.now())
21
+ TrackerDebugger::TrackerDebugger (rclcpp::Node & node) : diagnostic_updater_(&node), node_(node)
27
22
{
28
23
// declare debug parameters to decide whether to publish debug topics
29
24
loadParameters ();
@@ -39,7 +34,15 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node)
39
34
" debug/tentative_objects" , rclcpp::QoS{1 });
40
35
}
41
36
42
- // initialize stop watch and diagnostics
37
+ // initialize timestamps
38
+ const rclcpp::Time now = node_.now ();
39
+ last_input_stamp_ = now;
40
+ stamp_process_start_ = now;
41
+ stamp_process_end_ = now;
42
+ stamp_publish_start_ = now;
43
+ stamp_publish_output_ = now;
44
+
45
+ // setup diagnostics
43
46
setupDiagnostics ();
44
47
}
45
48
@@ -73,7 +76,11 @@ void TrackerDebugger::loadParameters()
73
76
74
77
void TrackerDebugger::checkDelay (diagnostic_updater::DiagnosticStatusWrapper & stat)
75
78
{
76
- const double delay = pipeline_latency_ms_; // [s]
79
+ if (!is_initialized_) {
80
+ stat.summary (diagnostic_msgs::msg::DiagnosticStatus::ERROR, " Measurement time is not set." );
81
+ return ;
82
+ }
83
+ const double & delay = pipeline_latency_ms_; // [s]
77
84
78
85
if (delay == 0.0 ) {
79
86
stat.summary (diagnostic_msgs::msg::DiagnosticStatus::OK, " Detection delay is not calculated." );
@@ -127,18 +134,21 @@ void TrackerDebugger::startPublishTime(const rclcpp::Time & now)
127
134
128
135
void TrackerDebugger::endPublishTime (const rclcpp::Time & now, const rclcpp::Time & object_time)
129
136
{
130
- const auto current_time = now;
137
+ // if the measurement time is not set, do not publish debug information
138
+ if (!is_initialized_) return ;
139
+
131
140
// pipeline latency: time from sensor measurement to publish, used for 'checkDelay'
132
- pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds () * 1e3 ;
133
- if (debug_settings_.publish_processing_time && is_initialized_) {
141
+ pipeline_latency_ms_ = (now - last_input_stamp_).seconds () * 1e3 ;
142
+
143
+ if (debug_settings_.publish_processing_time ) {
134
144
// processing latency: time between input and publish
135
- double processing_latency_ms = ((current_time - stamp_process_start_).seconds ()) * 1e3 ;
145
+ double processing_latency_ms = ((now - stamp_process_start_).seconds ()) * 1e3 ;
136
146
// processing time: only the time spent in the tracking processes
137
- double processing_time_ms = ((current_time - stamp_publish_start_).seconds () +
147
+ double processing_time_ms = ((now - stamp_publish_start_).seconds () +
138
148
(stamp_process_end_ - stamp_process_start_).seconds ()) *
139
149
1e3 ;
140
150
// cycle time: time between two consecutive publish
141
- double cyclic_time_ms = (current_time - stamp_publish_output_).seconds () * 1e3 ;
151
+ double cyclic_time_ms = (now - stamp_publish_output_).seconds () * 1e3 ;
142
152
// measurement to tracked-object time: time from the sensor measurement to the publishing object
143
153
// time If there is not latency compensation, this value is zero
144
154
double measurement_to_object_ms = (object_time - last_input_stamp_).seconds () * 1e3 ;
@@ -155,5 +165,5 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim
155
165
processing_time_publisher_->publish <tier4_debug_msgs::msg::Float64Stamped>(
156
166
" debug/meas_to_tracked_object_ms" , measurement_to_object_ms);
157
167
}
158
- stamp_publish_output_ = current_time ;
168
+ stamp_publish_output_ = now ;
159
169
}
0 commit comments