40 #include <gtest/gtest.h> 52 ROS_INFO(
"parent=%s", param.c_str());
53 ASSERT_EQ(param,
":ROS_NAMESPACE:parent");
56 TEST(namespaces, localParam)
60 ROS_INFO(
"~/local=%s", param.c_str());
61 ASSERT_EQ(param,
":ROS_NAMESPACE:NODE_NAME:local");
65 n.
param<std::string>(
"local", param2, param);
66 ASSERT_STREQ(param2.c_str(), param.c_str());
67 ASSERT_STREQ(param2.c_str(),
":ROS_NAMESPACE:NODE_NAME:local");
70 TEST(namespaces, globalParam)
74 ASSERT_EQ(param,
":global");
77 TEST(namespaces, otherNamespaceParam)
81 ASSERT_EQ(param,
":other_namespace:param");
87 ASSERT_EQ(name,
"/ROS_NAMESPACE/NODE_NAME");
89 ASSERT_EQ(nspace,
"/ROS_NAMESPACE");
93 main(
int argc,
char** argv)
95 testing::InitGoogleTest(&argc, argv);
98 return RUN_ALL_TESTS();
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
ROSCPP_DECL const std::string & getNamespace()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const