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