2727#include < ros/ros.h>
2828#include < controller_manager/controller_manager.h>
2929
30+ #include < diagnostic_msgs/DiagnosticArray.h>
31+ #include < diagnostic_msgs/DiagnosticStatus.h>
32+ #include < diagnostic_msgs/KeyValue.h>
33+
3034#include < csignal>
3135#include < ur_robot_driver/ros/hardware_interface.h>
3236
@@ -43,6 +47,46 @@ void signalHandler(int signum)
4347 exit (signum);
4448}
4549
50+ struct msgStats {
51+ std::chrono::duration<double > min_stat;
52+ std::chrono::duration<double > max_stat;
53+ std::chrono::duration<double > total_stat;
54+ };
55+
56+ void reset_msg_stats (msgStats &stats)
57+ {
58+ stats.min_stat = std::chrono::duration<double >::zero ();
59+ stats.max_stat = std::chrono::duration<double >::zero ();
60+ stats.total_stat = std::chrono::duration<double >::zero ();
61+ }
62+
63+ void update_msg_stats (std::chrono::duration<double > stat_elapsed,
64+ msgStats &stats)
65+ {
66+ if (stats.min_stat == std::chrono::duration<double >::zero () || stat_elapsed < stats.min_stat ) stats.min_stat = stat_elapsed;
67+ if (stats.max_stat == std::chrono::duration<double >::zero () || stat_elapsed > stats.max_stat ) stats.max_stat = stat_elapsed;
68+ stats.total_stat += stat_elapsed;
69+ }
70+
71+ void push_msg_stats (diagnostic_msgs::DiagnosticStatus &stat,
72+ std::string stat_name,
73+ msgStats msg_stats,
74+ long num_loops)
75+ {
76+ diagnostic_msgs::KeyValue min_stat_kv;
77+ min_stat_kv.key = " min " + stat_name + " (s)" ;
78+ min_stat_kv.value = std::to_string (msg_stats.min_stat .count ());
79+ stat.values .push_back (min_stat_kv);
80+ diagnostic_msgs::KeyValue max_stat_kv;
81+ max_stat_kv.key = " max " + stat_name + " (s)" ;
82+ max_stat_kv.value = std::to_string (msg_stats.max_stat .count ());
83+ stat.values .push_back (max_stat_kv);
84+ diagnostic_msgs::KeyValue avg_stat_kv;
85+ avg_stat_kv.key = " avg " + stat_name + " (s)" ;
86+ avg_stat_kv.value = std::to_string (msg_stats.total_stat .count () / num_loops);
87+ stat.values .push_back (avg_stat_kv);
88+ }
89+
4690int main (int argc, char ** argv)
4791{
4892 // Set up ROS.
@@ -53,6 +97,8 @@ int main(int argc, char** argv)
5397 ros::NodeHandle nh;
5498 ros::NodeHandle nh_priv (" ~" );
5599
100+ ros::Publisher diagnostic_pub = nh.advertise <diagnostic_msgs::DiagnosticArray>(" /diagnostics" , 1 );
101+
56102 // register signal SIGINT and signal handler
57103 signal (SIGINT, signalHandler);
58104
@@ -129,6 +175,35 @@ int main(int argc, char** argv)
129175
130176 double expected_cycle_time = 1.0 / (static_cast <double >(g_hw_interface->getControlFrequency ()));
131177
178+ msgStats period_stats;
179+ reset_msg_stats (period_stats);
180+ msgStats read_stats;
181+ reset_msg_stats (read_stats);
182+ msgStats cm_update_stats;
183+ reset_msg_stats (cm_update_stats);
184+ msgStats write_stats;
185+ reset_msg_stats (write_stats);
186+
187+ // sub-stats of the read method
188+ msgStats get_data_stats;
189+ reset_msg_stats (get_data_stats);
190+ msgStats read_data_stats;
191+ reset_msg_stats (read_data_stats);
192+ msgStats pub_io_stats;
193+ reset_msg_stats (pub_io_stats);
194+ msgStats pub_tool_stats;
195+ reset_msg_stats (pub_tool_stats);
196+ msgStats pub_pose_stats;
197+ reset_msg_stats (pub_pose_stats);
198+ msgStats pub_robot_stats;
199+ reset_msg_stats (pub_robot_stats);
200+ msgStats pub_temp_stats;
201+ reset_msg_stats (pub_temp_stats);
202+
203+ std::chrono::duration<double > last_diagnostics_duration = std::chrono::duration<double >::zero ();
204+
205+ long debug_loops = 0 ;
206+
132207 // Debug timing printout every 5 seconds
133208 const std::chrono::seconds debug_timing_period{5 };
134209 std::chrono::steady_clock::time_point debug_timing_start = std::chrono::steady_clock::now ();
@@ -144,23 +219,102 @@ int main(int argc, char** argv)
144219 if (trigger_low_frequency_logging) debug_timing_start = debug_timing_now;
145220
146221 // Receive current state from robot
222+ const std::chrono::steady_clock::time_point read_start = std::chrono::steady_clock::now ();
147223 g_hw_interface->read (timestamp, period);
224+ const std::chrono::duration<double > read_elapsed = std::chrono::steady_clock::now () - read_start;
225+ update_msg_stats (read_elapsed, read_stats);
226+ ur_driver::HardwareInterface::readStats read_substats = g_hw_interface->get_read_stats ();
227+ update_msg_stats (read_substats.get_data_elapsed , get_data_stats);
228+ update_msg_stats (read_substats.read_data_elapsed , read_data_stats);
229+ update_msg_stats (read_substats.pub_io_elapsed , pub_io_stats);
230+ update_msg_stats (read_substats.pub_tool_elapsed , pub_tool_stats);
231+ update_msg_stats (read_substats.pub_pose_elapsed , pub_pose_stats);
232+ update_msg_stats (read_substats.pub_robot_elapsed , pub_robot_stats);
233+ update_msg_stats (read_substats.pub_temp_elapsed , pub_temp_stats);
234+
148235
149236 // Get current time and elapsed time since last read
150237 timestamp = ros::Time::now ();
151238 stopwatch_now = std::chrono::steady_clock::now ();
152- period.fromSec (std::chrono::duration_cast<std::chrono::duration<double >>(stopwatch_now - stopwatch_last).count ());
239+ const std::chrono::duration<double > period_chrono = stopwatch_now - stopwatch_last;
240+ update_msg_stats (period_chrono, period_stats);
241+ period.fromSec (period_chrono.count ());
153242 stopwatch_last = stopwatch_now;
154243
244+ const std::chrono::steady_clock::time_point cm_update_start = std::chrono::steady_clock::now ();
155245 cm.update (timestamp, period, g_hw_interface->shouldResetControllers ());
246+ const std::chrono::duration<double > cm_update_elapsed = std::chrono::steady_clock::now () - cm_update_start;
247+ update_msg_stats (cm_update_elapsed, cm_update_stats);
156248
249+ const std::chrono::steady_clock::time_point write_start = std::chrono::steady_clock::now ();
157250 g_hw_interface->write (timestamp, period);
251+ const std::chrono::duration<double > write_elapsed = std::chrono::steady_clock::now () - write_start;
252+ update_msg_stats (write_elapsed, write_stats);
253+
254+ ++debug_loops;
255+
256+ // 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) {
260+ diagnostic_msgs::DiagnosticArray dia_array;
261+ diagnostic_msgs::DiagnosticStatus robot_status;
262+ robot_status.name = " ur_hardware_interface: Overall health" ;
263+ robot_status.level = diagnostic_msgs::DiagnosticStatus::OK;
264+ robot_status.message = " Looping" ;
265+ robot_status.hardware_id = " none" ;
266+
267+ diagnostic_msgs::KeyValue loop_durations_last;
268+ loop_durations_last.key = " Loop durations last (s)" ;
269+ loop_durations_last.value = std::to_string (total_elapsed.count ());
270+ robot_status.values .push_back (loop_durations_last);
271+ diagnostic_msgs::KeyValue num_loops;
272+ num_loops.key = " Number of loops" ;
273+ num_loops.value = std::to_string (debug_loops);
274+ robot_status.values .push_back (num_loops);
275+
276+ push_msg_stats (robot_status, " period loop" , period_stats, debug_loops);
277+ push_msg_stats (robot_status, " read" , read_stats, debug_loops);
278+ push_msg_stats (robot_status, " cm_update" , cm_update_stats, debug_loops);
279+ push_msg_stats (robot_status, " write" , write_stats, debug_loops);
280+ push_msg_stats (robot_status, " read: get_data" , get_data_stats, debug_loops);
281+ push_msg_stats (robot_status, " read: read_data" , read_data_stats, debug_loops);
282+ push_msg_stats (robot_status, " read: pub_io" , pub_io_stats, debug_loops);
283+ push_msg_stats (robot_status, " read: pub_tool" , pub_tool_stats, debug_loops);
284+ push_msg_stats (robot_status, " read: pub_pose" , pub_pose_stats, debug_loops);
285+ push_msg_stats (robot_status, " read: pub_robot" , pub_robot_stats, debug_loops);
286+ push_msg_stats (robot_status, " read: pub_temp" , pub_temp_stats, debug_loops);
287+
288+ diagnostic_msgs::KeyValue diagnostic_duration_kv;
289+ diagnostic_duration_kv.key = " Last diagnostic duration (s)" ;
290+ diagnostic_duration_kv.value = std::to_string (last_diagnostics_duration.count ());
291+ robot_status.values .push_back (diagnostic_duration_kv);
292+
293+ dia_array.status .push_back (robot_status);
294+ diagnostic_pub.publish (dia_array);
295+
296+ reset_msg_stats (period_stats);
297+ reset_msg_stats (read_stats);
298+ reset_msg_stats (cm_update_stats);
299+ reset_msg_stats (write_stats);
300+ reset_msg_stats (get_data_stats);
301+ reset_msg_stats (read_data_stats);
302+ reset_msg_stats (pub_io_stats);
303+ reset_msg_stats (pub_tool_stats);
304+ reset_msg_stats (pub_pose_stats);
305+ reset_msg_stats (pub_robot_stats);
306+ reset_msg_stats (pub_temp_stats);
307+ debug_loops = 0 ;
308+ debug_timing_start = debug_timing_now;
309+ last_diagnostics_duration = std::chrono::steady_clock::now () - debug_timing_now;
310+ }
311+
158312 // if (!control_rate.sleep())
159- if (period.toSec () > expected_cycle_time)
160- {
313+ // if (period.toSec() > expected_cycle_time)
314+ // {
161315 // ROS_WARN_STREAM("Could not keep cycle rate of " << expected_cycle_time * 1000 << "ms");
162316 // ROS_WARN_STREAM("Actual cycle time:" << period.toNSec() / 1000000.0 << "ms");
163- }
317+ // }
164318 }
165319
166320 spinner.stop ();
0 commit comments