36 #include "diagnostic_msgs/SelfTest.h" 41 TEST(SelfTest, runSelfTest)
49 nh_private.
param(
"max_delay", max_delay, 60.);
50 ASSERT_FALSE(node_to_test.empty()) <<
"selftest_rostest needs the \"node_to_test\" parameter.";
52 std::string service_name = node_to_test+
"/self_test";
55 diagnostic_msgs::SelfTest srv;
59 diagnostic_msgs::SelfTest::Response &res = srv.response;
68 EXPECT_TRUE(res.passed) <<
"Overall self-test FAILED.";
70 printf(
"Self test %s for device with id: [%s]\n", passfail.c_str(), res.id.c_str());
72 for (
size_t i = 0; i < res.status.size(); i++)
74 printf(
"%2d) %s\n", ((
int) i + 1), res.status[i].name.c_str());
75 if (res.status[i].level == 0)
77 else if (res.status[i].level == 1)
78 printf(
" [WARNING]: ");
82 printf(
"%s\n", res.status[i].message.c_str());
84 EXPECT_EQ(0, res.status[i].level) << res.status[i].name <<
" did not PASS: " << res.status[i].message;
86 for (
size_t j = 0; j < res.status[i].values.size(); j++)
87 printf(
" [%s] %s\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value.c_str());
94 FAIL() <<
"Unable to trigger self-test.";
95 printf(
"Failed to call service.\n");
99 int main(
int argc,
char **argv)
101 ros::init(argc, argv,
"selftest_nodetest");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void InitGoogleTest(int *argc, char **argv)
TEST(SelfTest, runSelfTest)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define EXPECT_EQ(expected, actual)
int main(int argc, char **argv)
int RUN_ALL_TESTS() GTEST_MUST_USE_RESULT_
#define EXPECT_TRUE(condition)
#define ASSERT_FALSE(condition)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)