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
00036
00037
00038
00039 #include <gtest/gtest.h>
00040 #include <std_msgs/Bool.h>
00041 #include <std_msgs/Byte.h>
00042 #include <std_msgs/Empty.h>
00043 #include <std_msgs/String.h>
00044 #include <std_msgs/Float32.h>
00045 #include <std_msgs/Float64.h>
00046 #include <ros/ros.h>
00047
00048 TEST(DifferentNamespaces, NodeletPrivateNodehandle) {
00049 ros::NodeHandle nh;
00050 ros::Duration(2).sleep();
00051 ros::master::V_TopicInfo master_topics;
00052 ros::master::getTopics(master_topics);
00053 bool found_topic = false;
00054
00055 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00056 const ros::master::TopicInfo& info = *it;
00057 if (info.datatype.compare("std_msgs/Bool") == 0) {
00058 found_topic = true;
00059 EXPECT_STREQ("/nodelet_namespace/nodehandle_test/private", info.name.c_str());
00060 }
00061 }
00062 EXPECT_TRUE(found_topic);
00063 }
00064
00065 TEST(DifferentNamespaces, NodeletNamespacedNodehandle) {
00066 ros::NodeHandle nh;
00067 ros::Duration(2).sleep();
00068 ros::master::V_TopicInfo master_topics;
00069 ros::master::getTopics(master_topics);
00070 bool found_topic = false;
00071
00072 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00073 const ros::master::TopicInfo& info = *it;
00074 if (info.datatype.compare("std_msgs/Byte") == 0) {
00075 found_topic = true;
00076 EXPECT_STREQ("/nodelet_namespace/namespaced", info.name.c_str());
00077 }
00078 }
00079 EXPECT_TRUE(found_topic);
00080 }
00081
00082 TEST(DifferentNamespaces, NodeletGlobalNodehandle) {
00083 ros::NodeHandle nh;
00084 ros::Duration(2).sleep();
00085 ros::master::V_TopicInfo master_topics;
00086 ros::master::getTopics(master_topics);
00087 bool found_topic = false;
00088
00089 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00090 const ros::master::TopicInfo& info = *it;
00091 if (info.datatype.compare("std_msgs/Time") == 0) {
00092 found_topic = true;
00093 EXPECT_STREQ("/global", info.name.c_str());
00094 }
00095 }
00096 EXPECT_TRUE(found_topic);
00097 }
00098
00099 TEST(DifferentNamespaces, NodePrivateNodehandle) {
00100 ros::NodeHandle nh("~");
00101 ros::Publisher pub = nh.advertise<std_msgs::Empty>("private", 10);
00102 ros::master::V_TopicInfo master_topics;
00103 ros::master::getTopics(master_topics);
00104 bool found_topic = false;
00105
00106 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00107 const ros::master::TopicInfo& info = *it;
00108 if (info.datatype.compare("std_msgs/Empty") == 0) {
00109 found_topic = true;
00110 EXPECT_STREQ("/test_namespace/test_nodehandles/private", info.name.c_str());
00111 }
00112 }
00113 EXPECT_TRUE(found_topic);
00114 }
00115
00116 TEST(DifferentNamespaces, NodeNamespacedNodehandle) {
00117 ros::NodeHandle nh;
00118 ros::Publisher pub = nh.advertise<std_msgs::String>("namespaced", 10);
00119 ros::master::V_TopicInfo master_topics;
00120 ros::master::getTopics(master_topics);
00121 bool found_topic = false;
00122
00123 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00124 const ros::master::TopicInfo& info = *it;
00125 if (info.datatype.compare("std_msgs/String") == 0) {
00126 found_topic = true;
00127 EXPECT_STREQ("/test_namespace/namespaced", info.name.c_str());
00128 }
00129 }
00130 EXPECT_TRUE(found_topic);
00131 }
00132
00133 TEST(DifferentNamespaces, NodeGlobalNodehandle) {
00134 ros::NodeHandle nh;
00135 ros::Publisher pub = nh.advertise<std_msgs::Float32>("/public", 10);
00136 ros::master::V_TopicInfo master_topics;
00137 ros::master::getTopics(master_topics);
00138 bool found_topic = false;
00139
00140 for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
00141 const ros::master::TopicInfo& info = *it;
00142 if (info.datatype.compare("std_msgs/Float32") == 0) {
00143 found_topic = true;
00144 EXPECT_STREQ("/public", info.name.c_str());
00145 }
00146 }
00147 EXPECT_TRUE(found_topic);
00148 }
00149
00150 int main(int argc, char **argv) {
00151 testing::InitGoogleTest(&argc, argv);
00152 ros::init(argc, argv, "test_nodehandles_different_namespaces");
00153 return RUN_ALL_TESTS();
00154 }