30 #include <gtest/gtest.h>
34 #include <std_msgs/Empty.h>
50 for (
auto i=0; i < num; ++i)
61 void emptyCb(
const std_msgs::EmptyConstPtr &msg)
68 bool connection_called =
false;
70 connection_called =
true;
72 ros::Publisher test_pub = nh_.advertise<std_msgs::Empty>(
"test", 1,
82 EXPECT_TRUE(connection_called);
84 ASSERT_TRUE(nh_.getEnableDocs());
85 auto doc_msg = nh_.getDocMsg();
87 bool found_test_topic=
false;
88 for (
const auto &topic : doc_msg.topics)
90 if (topic.name ==
"test")
92 found_test_topic =
true;
95 EXPECT_TRUE(found_test_topic);
100 bool cb_called=
false;
101 auto empty_cb = [&cb_called](
const std_msgs::EmptyConstPtr &
msg){ cb_called =
true; };
111 empty_pub.
publish(boost::make_shared<std_msgs::Empty>());
114 EXPECT_TRUE(cb_called);
116 ASSERT_TRUE(nh_.getEnableDocs());
117 auto doc_msg = nh_.getDocMsg();
119 bool found_test_topic=
false;
120 for (
const auto &topic : doc_msg.topics)
122 if (topic.name ==
"test")
124 found_test_topic =
true;
127 EXPECT_TRUE(found_test_topic);
130 int main(
int argc,
char **argv)
132 ros::init(argc, argv,
"swri_node_handle_test");
133 testing::InitGoogleTest(&argc, argv);
134 int result = RUN_ALL_TESTS();