Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include <iostream>
00030 #include <boost/bind.hpp>
00031 #include <boost/thread.hpp>
00032 #include <boost/foreach.hpp>
00033 #include <ros/ros.h>
00034
00035 #include <diagnostic_msgs/DiagnosticArray.h>
00036 #include <scriptable_monitor/ScriptableMonitorNode.h>
00037
00038 using namespace std;
00039
00040 #define foreach BOOST_FOREACH
00041
00042 void diagnosticPublisher(ros::NodeHandle& node, ScriptHost& scriptHost) {
00043
00044 ros::Publisher publisher = node.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 100, false);
00045
00046 while (ros::ok()) {
00047 diagnostic_msgs::DiagnosticArray array;
00048 array.header.stamp = ros::Time::now();
00049
00050 foreach(DiagnosticStatusPtr status, scriptHost.getDiagnosticStatusesAndClear()) {
00051 array.status.push_back(*status);
00052 }
00053
00054 publisher.publish(array);
00055
00056 boost::this_thread::sleep(boost::posix_time::seconds(1));
00057 }
00058
00059 }
00060
00061 int main(int argc, char **argv) {
00062 ros::init(argc, argv, "scriptable_monitor");
00063 ros::NodeHandle node("~");
00064 ScriptableMonitorNode scriptNode;
00065 boost::thread diagnosticPublishThread(boost::bind(diagnosticPublisher, boost::ref(node), boost::ref(scriptNode.getScriptHost())));
00066 ros::spin();
00067 return 0;
00068 }