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 #include <string>
00037 #include <sstream>
00038 #include <fstream>
00039
00040 #include <gtest/gtest.h>
00041
00042 #include <time.h>
00043 #include <stdlib.h>
00044
00045 #include <ros/ros.h>
00046 #include <ros/param.h>
00047
00048 TEST(namespaces, param)
00049 {
00050 std::string param;
00051 ASSERT_TRUE( ros::param::get( "parent", param ) );
00052 ROS_INFO("parent=%s", param.c_str());
00053 ASSERT_EQ(param, ":ROS_NAMESPACE:parent");
00054 }
00055
00056 TEST(namespaces, localParam)
00057 {
00058 std::string param;
00059 ASSERT_TRUE( ros::param::get( "~/local", param ) );
00060 ROS_INFO("~/local=%s", param.c_str());
00061 ASSERT_EQ(param, ":ROS_NAMESPACE:NODE_NAME:local");
00062
00063 ros::NodeHandle n("~");
00064 std::string param2;
00065 n.param<std::string>("local", param2, param);
00066 ASSERT_STREQ(param2.c_str(), param.c_str());
00067 ASSERT_STREQ(param2.c_str(), ":ROS_NAMESPACE:NODE_NAME:local");
00068 }
00069
00070 TEST(namespaces, globalParam)
00071 {
00072 std::string param;
00073 ASSERT_TRUE( ros::param::get( "/global", param ) );
00074 ASSERT_EQ(param, ":global");
00075 }
00076
00077 TEST(namespaces, otherNamespaceParam)
00078 {
00079 std::string param;
00080 ASSERT_TRUE( ros::param::get( "/other_namespace/param", param ) );
00081 ASSERT_EQ(param, ":other_namespace:param");
00082 }
00083
00084 TEST(namespaces, name)
00085 {
00086 std::string name = ros::this_node::getName();
00087 ASSERT_EQ(name, "/ROS_NAMESPACE/NODE_NAME");
00088 std::string nspace = ros::this_node::getNamespace();
00089 ASSERT_EQ(nspace, "/ROS_NAMESPACE");
00090 }
00091
00092 int
00093 main(int argc, char** argv)
00094 {
00095 testing::InitGoogleTest(&argc, argv);
00096 ros::init( argc, argv, "namespaces" );
00097
00098 return RUN_ALL_TESTS();
00099 }