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
00044
00045 class MyNode
00046 {
00047 public:
00048
00049
00050 self_test::TestRunner self_test_;
00051
00052
00053 double some_val;
00054
00055 ros::NodeHandle nh_;
00056
00057 MyNode() : self_test_()
00058 {
00059 self_test_.add("Pretest", this, &MyNode::pretest );
00060
00061 self_test_.add("ID Lookup", this, &MyNode::test1);
00062 self_test_.add("Exception generating test", this, &MyNode::test2);
00063 self_test_.add("Value generating test", this, &MyNode::test3);
00064 self_test_.add("Value testing test", this, &MyNode::test4);
00065
00066 self_test_.add("Posttest", this, &MyNode::pretest );
00067 }
00068
00069 void pretest(diagnostic_updater::DiagnosticStatusWrapper& status)
00070 {
00071 ROS_INFO("Doing preparation stuff before we run our test.\n");
00072 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Pretest completed successfully.");
00073
00074 some_val = 1.0;
00075 }
00076
00077 void test1(diagnostic_updater::DiagnosticStatusWrapper& status)
00078 {
00079
00080 char ID[] = "12345";
00081 bool lookup_successful = true;
00082
00083 if (lookup_successful)
00084 {
00085 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "ID Lookup successful");
00086
00087 self_test_.setID(ID);
00088
00089 } else {
00090 status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "ID Lookup failed");
00091 }
00092 }
00093
00094
00095 void test2(diagnostic_updater::DiagnosticStatusWrapper& status)
00096 {
00097 status.level = 0;
00098
00099 throw std::runtime_error("we did something that threw an exception");
00100
00101
00102 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "We made it past the exception throwing statement.");
00103 }
00104
00105 void test3(diagnostic_updater::DiagnosticStatusWrapper& status)
00106 {
00107 some_val += 41.0;
00108
00109 status.add("some value", some_val);
00110 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "We successfully changed the value.");
00111 }
00112
00113 void test4(diagnostic_updater::DiagnosticStatusWrapper& status)
00114 {
00115 if (some_val == 42.0)
00116 {
00117 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "We observed the change in value");
00118 }
00119 else
00120 {
00121 status.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "We failed to observe the change in value, it is currently %f.", some_val);
00122 }
00123 }
00124
00125 void posttest(diagnostic_updater::DiagnosticStatusWrapper& status)
00126 {
00127 ROS_INFO("Doing cleanup stuff after we run our test.\n");
00128 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Posttest completed successfully.");
00129 }
00130
00131 bool spin()
00132 {
00133 while (nh_.ok())
00134 {
00135 ros::Duration(1).sleep();
00136
00137 self_test_.checkTest();
00138 }
00139 return true;
00140 }
00141 };
00142
00143 int
00144 main(int argc, char** argv)
00145 {
00146 ros::init(argc, argv, "my_node");
00147
00148 MyNode n;
00149
00150 n.spin();
00151
00152 return(0);
00153 }