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> 45 #include <std_msgs/Float64.h> 48 TEST(DifferentNamespaces, NodeletPrivateNodehandle) {
53 bool found_topic =
false;
55 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
57 if (info.
datatype.compare(
"std_msgs/Bool") == 0) {
59 EXPECT_STREQ(
"/nodelet_namespace/nodehandle_test/private", info.
name.c_str());
62 EXPECT_TRUE(found_topic);
65 TEST(DifferentNamespaces, NodeletNamespacedNodehandle) {
70 bool found_topic =
false;
72 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
74 if (info.
datatype.compare(
"std_msgs/Byte") == 0) {
76 EXPECT_STREQ(
"/nodelet_namespace/namespaced", info.
name.c_str());
79 EXPECT_TRUE(found_topic);
82 TEST(DifferentNamespaces, NodeletGlobalNodehandle) {
87 bool found_topic =
false;
89 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
91 if (info.
datatype.compare(
"std_msgs/Time") == 0) {
93 EXPECT_STREQ(
"/global", info.
name.c_str());
96 EXPECT_TRUE(found_topic);
99 TEST(DifferentNamespaces, NodePrivateNodehandle) {
104 bool found_topic =
false;
106 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
108 if (info.
datatype.compare(
"std_msgs/Empty") == 0) {
110 EXPECT_STREQ(
"/test_namespace/test_nodehandles/private", info.
name.c_str());
113 EXPECT_TRUE(found_topic);
116 TEST(DifferentNamespaces, NodeNamespacedNodehandle) {
121 bool found_topic =
false;
123 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
125 if (info.
datatype.compare(
"std_msgs/String") == 0) {
127 EXPECT_STREQ(
"/test_namespace/namespaced", info.
name.c_str());
130 EXPECT_TRUE(found_topic);
133 TEST(DifferentNamespaces, NodeGlobalNodehandle) {
138 bool found_topic =
false;
140 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
142 if (info.
datatype.compare(
"std_msgs/Float32") == 0) {
144 EXPECT_STREQ(
"/public", info.
name.c_str());
147 EXPECT_TRUE(found_topic);
150 int main(
int argc,
char **argv) {
151 testing::InitGoogleTest(&argc, argv);
152 ros::init(argc, argv,
"test_nodehandles_different_namespaces");
153 return RUN_ALL_TESTS();
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
TEST(DifferentNamespaces, NodeletPrivateNodehandle)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)