Skip to content

Commit a3befb3

Browse files
committed
fix from rebase
1 parent 17a705e commit a3befb3

File tree

1 file changed

+5
-7
lines changed

1 file changed

+5
-7
lines changed

ur_robot_driver/src/ros/hardware_interface_node.cpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -216,7 +216,6 @@ int main(int argc, char** argv)
216216
// This is mostly used to track low-frequency information like joint temperature
217217
const bool trigger_low_frequency_logging = elapsed_since_debug > debug_timing_period;
218218
g_hw_interface->shouldLogTemperature(trigger_low_frequency_logging);
219-
if (trigger_low_frequency_logging) debug_timing_start = debug_timing_now;
220219

221220
// Receive current state from robot
222221
const std::chrono::steady_clock::time_point read_start = std::chrono::steady_clock::now();
@@ -254,9 +253,8 @@ int main(int argc, char** argv)
254253
++debug_loops;
255254

256255
// Check if it's time to print
257-
const std::chrono::steady_clock::time_point debug_timing_now = std::chrono::steady_clock::now();
258-
const std::chrono::duration<double> total_elapsed = debug_timing_now - debug_timing_start;
259-
if (total_elapsed > debug_timing_period) {
256+
if (trigger_low_frequency_logging) {
257+
const std::chrono::steady_clock::time_point diagnostic_start = std::chrono::steady_clock::now();
260258
diagnostic_msgs::DiagnosticArray dia_array;
261259
diagnostic_msgs::DiagnosticStatus robot_status;
262260
robot_status.name = "ur_hardware_interface: Overall health";
@@ -266,7 +264,7 @@ int main(int argc, char** argv)
266264

267265
diagnostic_msgs::KeyValue loop_durations_last;
268266
loop_durations_last.key = "Loop durations last (s)";
269-
loop_durations_last.value = std::to_string(total_elapsed.count());
267+
loop_durations_last.value = std::to_string(elapsed_since_debug.count());
270268
robot_status.values.push_back(loop_durations_last);
271269
diagnostic_msgs::KeyValue num_loops;
272270
num_loops.key = "Number of loops";
@@ -305,9 +303,9 @@ int main(int argc, char** argv)
305303
reset_msg_stats(pub_robot_stats);
306304
reset_msg_stats(pub_temp_stats);
307305
debug_loops = 0;
308-
debug_timing_start = debug_timing_now;
309-
last_diagnostics_duration = std::chrono::steady_clock::now() - debug_timing_now;
306+
last_diagnostics_duration = std::chrono::steady_clock::now() - diagnostic_start;
310307
}
308+
if (trigger_low_frequency_logging) debug_timing_start = debug_timing_now;
311309

312310
// if (!control_rate.sleep())
313311
// if (period.toSec() > expected_cycle_time)

0 commit comments

Comments
 (0)