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 TEST(SelfTest, runSelfTest)
00042 {
00043 ros::NodeHandle nh;
00044 ros::NodeHandle nh_private("~");
00045
00046 std::string node_to_test;
00047 double max_delay;
00048 nh_private.param("node_to_test", node_to_test, std::string());
00049 nh_private.param("max_delay", max_delay, 60.);
00050 ASSERT_FALSE(node_to_test.empty()) << "selftest_rostest needs the \"node_to_test\" parameter.";
00051
00052 std::string service_name = node_to_test+"/self_test";
00053 ros::service::waitForService(service_name, max_delay);
00054
00055 diagnostic_msgs::SelfTest srv;
00056
00057 if (nh.serviceClient<diagnostic_msgs::SelfTest>(service_name).call(srv))
00058 {
00059 diagnostic_msgs::SelfTest::Response &res = srv.response;
00060
00061 std::string passfail;
00062
00063 if (res.passed)
00064 passfail = "PASSED";
00065 else
00066 passfail = "FAILED";
00067
00068 EXPECT_TRUE(res.passed) << "Overall self-test FAILED.";
00069
00070 printf("Self test %s for device with id: [%s]\n", passfail.c_str(), res.id.c_str());
00071
00072 for (size_t i = 0; i < res.status.size(); i++)
00073 {
00074 printf("%2d) %s\n", ((int) i + 1), res.status[i].name.c_str());
00075 if (res.status[i].level == 0)
00076 printf(" [OK]: ");
00077 else if (res.status[i].level == 1)
00078 printf(" [WARNING]: ");
00079 else
00080 printf(" [ERROR]: ");
00081
00082 printf("%s\n", res.status[i].message.c_str());
00083
00084 EXPECT_EQ(0, res.status[i].level) << res.status[i].name << " did not PASS: " << res.status[i].message;
00085
00086 for (size_t j = 0; j < res.status[i].values.size(); j++)
00087 printf(" [%s] %s\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value.c_str());
00088
00089 printf("\n");
00090 }
00091 }
00092 else
00093 {
00094 FAIL() << "Unable to trigger self-test.";
00095 printf("Failed to call service.\n");
00096 }
00097 }
00098
00099 int main(int argc, char **argv)
00100 {
00101 ros::init(argc, argv, "selftest_nodetest");
00102 testing::InitGoogleTest(&argc, argv);
00103 return RUN_ALL_TESTS();
00104 }
00105