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 #include <ros/names.h>
00048
00049 TEST(roscpp, parameterRemapping)
00050 {
00051 std::string param;
00052 ASSERT_TRUE(ros::param::get("mapfrom", param));
00053 ASSERT_STREQ(ros::names::resolve("mapfrom").c_str(), "/mapto");
00054
00055 ASSERT_TRUE(ros::param::get("/mapto", param));
00056 ASSERT_STREQ(ros::names::resolve("/mapfrom").c_str(), "/mapto");
00057 }
00058
00059 TEST(roscpp, nodeNameRemapping)
00060 {
00061 std::string node_name = ros::this_node::getName();
00062 ASSERT_STREQ(node_name.c_str(), "/name_remapped");
00063 }
00064
00065 TEST(roscpp, cleanName)
00066 {
00067 ASSERT_STREQ(ros::names::clean("////asdf///").c_str(), "/asdf");
00068 ASSERT_STREQ(ros::names::clean("////asdf///jioweioj").c_str(), "/asdf/jioweioj");
00069 ASSERT_STREQ(ros::names::clean("////asdf///jioweioj/").c_str(), "/asdf/jioweioj");
00070 }
00071
00072 TEST(RoscppHandles, nodeHandleNameRemapping)
00073 {
00074 ros::M_string remap;
00075 remap["a"] = "b";
00076 remap["/a/a"] = "/a/b";
00077 remap["c"] = "/a/c";
00078 remap["d/d"] = "/c/e";
00079 remap["d/e"] = "c/f";
00080 ros::NodeHandle n("", remap);
00081
00082 EXPECT_STREQ(n.resolveName("a").c_str(), "/b");
00083 EXPECT_STREQ(n.resolveName("/a/a").c_str(), "/a/b");
00084 EXPECT_STREQ(n.resolveName("c").c_str(), "/a/c");
00085 EXPECT_STREQ(n.resolveName("d/d").c_str(), "/c/e");
00086
00087 ros::NodeHandle n2("z", remap);
00088 EXPECT_STREQ(n2.resolveName("a").c_str(), "/z/b");
00089 EXPECT_STREQ(n2.resolveName("/a/a").c_str(), "/a/b");
00090 EXPECT_STREQ(n2.resolveName("c").c_str(), "/a/c");
00091 EXPECT_STREQ(n2.resolveName("d/d").c_str(), "/c/e");
00092 EXPECT_STREQ(n2.resolveName("d/e").c_str(), "/z/c/f");
00093 }
00094
00095 int
00096 main(int argc, char** argv)
00097 {
00098 testing::InitGoogleTest(&argc, argv);
00099 ros::init( argc, argv, "name_remapping" );
00100 ros::NodeHandle nh;
00101
00102 return RUN_ALL_TESTS();
00103 }