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 #include <ros/ros.h>
00031 #include <gtest/gtest.h>
00032
00033 static int argc_;
00034 static char** argv_;
00035
00036 TEST(RemappingTest, remapping_test)
00037 {
00038 EXPECT_TRUE(argc_ >= 3);
00039
00040 std::string expected_base_ns = argv_[1];
00041 std::string expected_sub_ns = argv_[2];
00042
00043 ros::NodeHandle nh;
00044
00045
00046 bool use_local_remap = false;
00047 EXPECT_TRUE(nh.getParam("use_local_remap", use_local_remap))
00048 << "Param [~use_local_remap] must be defined\n";
00049
00050 if (use_local_remap)
00051 {
00052 std::string remap_from, remap_to;
00053 EXPECT_TRUE(nh.getParam("remap_from", remap_from)) << "Param [~remap_from] must be defined\n";
00054 EXPECT_TRUE(nh.getParam("remap_to", remap_to)) << "Param [~remap_to] must be defined\n";
00055
00056
00057 ros::M_string local_remappings;
00058 local_remappings.insert(std::make_pair(remap_from, remap_to));
00059
00060 ros::NodeHandle base_nh(nh, "base_namespace", local_remappings);
00061 EXPECT_TRUE(base_nh.getNamespace() == expected_base_ns)
00062 << "Error: \"" << base_nh.getNamespace() << "\" != \"" << expected_base_ns << "\"\n";
00063
00064 ros::NodeHandle sub_nh(base_nh, "sub_namespace");
00065 EXPECT_TRUE(sub_nh.getNamespace() == expected_sub_ns)
00066 << "Error: \"" << sub_nh.getNamespace() << "\" != \"" << expected_sub_ns << "\"\n";
00067 }
00068 else
00069 {
00070 std::cout << "***********************************************************************\n";
00071 ros::NodeHandle base_nh(nh, "base_namespace");
00072 EXPECT_EQ(base_nh.getNamespace(), expected_base_ns);
00073
00074 ros::NodeHandle sub_nh(base_nh, "sub_namespace");
00075 EXPECT_EQ(sub_nh.getNamespace(), expected_sub_ns);
00076 }
00077 }
00078
00079 int main(int argc, char** argv)
00080 {
00081 testing::InitGoogleTest(&argc, argv);
00082 ros::init(argc, argv, "remapping_tester");
00083 argc_ = argc;
00084 argv_ = argv;
00085 return RUN_ALL_TESTS();
00086 }