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_STREQ(ros::names::resolve("test_full").c_str(), "/b/test_full");
00053 ASSERT_TRUE(ros::param::get("test_full", param));
00054 ASSERT_STREQ(ros::names::resolve("/a/test_full").c_str(), "/b/test_full");
00055 ASSERT_TRUE(ros::param::get("/a/test_full", param));
00056
00057 ASSERT_STREQ(ros::names::resolve("test_local").c_str(), "/a/test_local2");
00058 ASSERT_TRUE(ros::param::get("test_local", param));
00059 ASSERT_STREQ(ros::names::resolve("/a/test_local").c_str(), "/a/test_local2");
00060 ASSERT_TRUE(ros::param::get("/a/test_local", param));
00061
00062 ASSERT_STREQ(ros::names::resolve("test_relative").c_str(), "/b/test_relative");
00063 ASSERT_TRUE(ros::param::get("test_relative", param));
00064 ASSERT_STREQ(ros::names::resolve("/a/test_relative").c_str(), "/b/test_relative");
00065 ASSERT_TRUE(ros::param::get("/a/test_relative", param));
00066 }
00067
00068 TEST(roscpp, nodeNameRemapping)
00069 {
00070 std::string node_name = ros::this_node::getName();
00071 ASSERT_STREQ(node_name.c_str(), "/a/name_remapped_with_ns");
00072 }
00073 int
00074 main(int argc, char** argv)
00075 {
00076 testing::InitGoogleTest(&argc, argv);
00077 ros::init( argc, argv, "name_remapping_with_ns" );
00078 ros::NodeHandle nh;
00079
00080 return RUN_ALL_TESTS();
00081 }