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
00035 #include <ros/ros.h>
00036
00037 #include "diagnostic_msgs/SelfTest.h"
00038
00039 #include "self_test/self_test.h"
00040
00041 #include <stdexcept>
00042
00043 class MyNode
00044 {
00045 public:
00046
00047
00048 self_test::TestRunner self_test_;
00049
00050
00051 double some_val;
00052
00053 ros::NodeHandle nh_;
00054
00055 MyNode() : self_test_()
00056 {
00057 self_test_.add("Pretest", this, &MyNode::pretest );
00058
00059 self_test_.add("ID Lookup", this, &MyNode::test1);
00060 self_test_.add("Value generating test", this, &MyNode::test3);
00061 self_test_.add("Value testing test", this, &MyNode::test4);
00062
00063 self_test_.add("Posttest", this, &MyNode::pretest );
00064 }
00065
00066 void pretest(diagnostic_updater::DiagnosticStatusWrapper& status)
00067 {
00068 ROS_INFO("Doing preparation stuff before we run our test.\n");
00069 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Pretest completed successfully.");
00070
00071 some_val = 1.0;
00072 }
00073
00074 void test1(diagnostic_updater::DiagnosticStatusWrapper& status)
00075 {
00076 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "ID not set");
00077 }
00078
00079 void test3(diagnostic_updater::DiagnosticStatusWrapper& status)
00080 {
00081 some_val += 41.0;
00082
00083 status.add("some value", some_val);
00084 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "We successfully changed the value.");
00085 }
00086
00087 void test4(diagnostic_updater::DiagnosticStatusWrapper& status)
00088 {
00089 if (some_val == 42.0)
00090 {
00091 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "We observed the change in value");
00092 }
00093 else
00094 {
00095 status.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "We failed to observe the change in value, it is currently %f.", some_val);
00096 }
00097 }
00098
00099 void posttest(diagnostic_updater::DiagnosticStatusWrapper& status)
00100 {
00101 ROS_INFO("Doing cleanup stuff after we run our test.\n");
00102 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Posttest completed successfully.");
00103 }
00104
00105 bool spin()
00106 {
00107 while (nh_.ok())
00108 {
00109 ros::Duration(1).sleep();
00110
00111 self_test_.checkTest();
00112 }
00113 return true;
00114 }
00115 };
00116
00117 int
00118 main(int argc, char** argv)
00119 {
00120 ros::init(argc, argv, "my_node");
00121
00122 MyNode n;
00123
00124 n.spin();
00125
00126 return(0);
00127 }