39 #include <gtest/gtest.h> 40 #include <std_msgs/Bool.h> 41 #include <std_msgs/Byte.h> 42 #include <std_msgs/Empty.h> 43 #include <std_msgs/String.h> 44 #include <std_msgs/Float32.h> 47 TEST(ManagerNamespaced, NodeletPrivateNodehandle) {
52 bool found_topic =
false;
54 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
56 if (info.
datatype.compare(
"std_msgs/Bool") == 0) {
58 EXPECT_STREQ(
"/nodehandle_test/private", info.
name.c_str());
61 EXPECT_TRUE(found_topic);
83 TEST(ManagerNamespaced, NodeletGlobalNodehandle) {
88 bool found_topic =
false;
90 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
92 if (info.
datatype.compare(
"std_msgs/Time") == 0) {
94 EXPECT_STREQ(
"/global", info.
name.c_str());
97 EXPECT_TRUE(found_topic);
100 TEST(ManagerNamespaced, NodePrivateNodehandle) {
105 bool found_topic =
false;
107 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
109 if (info.
datatype.compare(
"std_msgs/Empty") == 0) {
111 EXPECT_STREQ(
"/test_nodehandles/private", info.
name.c_str());
114 EXPECT_TRUE(found_topic);
117 TEST(ManagerNamespaced, NodeNamespacedNodehandle) {
122 bool found_topic =
false;
124 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
126 if (info.
datatype.compare(
"std_msgs/String") == 0) {
128 EXPECT_STREQ(
"/namespaced", info.
name.c_str());
131 EXPECT_TRUE(found_topic);
134 TEST(ManagerNamespaced, NodeGlobalNodehandle) {
139 bool found_topic =
false;
141 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
143 if (info.
datatype.compare(
"std_msgs/Float32") == 0) {
145 EXPECT_STREQ(
"/public", info.
name.c_str());
148 EXPECT_TRUE(found_topic);
151 int main(
int argc,
char **argv) {
152 testing::InitGoogleTest(&argc, argv);
153 ros::init(argc, argv,
"test_nodehandles_manager_namespaced");
154 return RUN_ALL_TESTS();
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
std::vector< TopicInfo > V_TopicInfo
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TEST(ManagerNamespaced, NodeletPrivateNodehandle)