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
00032
00033
00034
00035 #include "ros/ros.h"
00036 #include "diagnostic_msgs/SelfTest.h"
00037
00038 #include <gtest/gtest.h>
00039 #include <string>
00040
00041 bool doTest(ros::NodeHandle nh)
00042 {
00043 diagnostic_msgs::SelfTest srv;
00044
00045 if (nh.serviceClient<diagnostic_msgs::SelfTest>("self_test").call(srv))
00046 {
00047 diagnostic_msgs::SelfTest::Response &res = srv.response;
00048
00049 std::string passfail;
00050
00051 if (res.passed)
00052 passfail = "PASSED";
00053 else
00054 passfail = "FAILED";
00055
00056 printf("Self test %s for device with id: [%s]\n", passfail.c_str(), res.id.c_str());
00057
00058
00059 for (size_t i = 0; i < res.status.size(); i++)
00060 {
00061 printf("%2zd) %s\n", i + 1, res.status[i].name.c_str());
00062 if (res.status[i].level == 0)
00063 printf(" [OK]: ");
00064 else if (res.status[i].level == 1)
00065 printf(" [WARNING]: ");
00066 else
00067 printf(" [ERROR]: ");
00068
00069 printf("%s\n", res.status[i].message.c_str());
00070
00071 for (size_t j = 0; j < res.status[i].values.size(); j++)
00072 printf(" [%s] %s\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value.c_str());
00073
00074 printf("\n");
00075 }
00076 return res.passed;
00077 }
00078 else
00079 {
00080 printf("Failed to call service.\n");
00081 return false;
00082 }
00083 }
00084
00085 int main(int argc, char **argv)
00086 {
00087 ros::init(argc, argv, "run_selftest", ros::init_options::AnonymousName);
00088 if (argc != 2)
00089 {
00090 printf("usage: run_selftest name\n");
00091 return 1;
00092 }
00093
00094 ros::NodeHandle nh(argv[1]);
00095 return !doTest(nh);
00096 }
00097