13 std::ifstream fin(file_name.c_str());
14 ROS_INFO(
"opening yaml file %s", file_name.c_str());
16 ROS_INFO(
"Unable to open yaml file %s", file_name.c_str());
21 ROS_INFO(
"Unable to create YAML parser for marker_set");
27 ROS_INFO(
"opening yaml file with new yaml-cpp %s", file_name.c_str());
28 if ( !(access(file_name.c_str(), F_OK) != -1)) {
29 ROS_INFO(
"file not exists :%s", file_name.c_str());
32 doc = YAML::LoadFile(file_name);
34 for (
int i=0; i<
doc.size() ;i++) {
35 std::string
text, topic_name;
36 const YAML::Node& single_menu =
doc[i];
38 single_menu[
"text"] >>
text;
39 single_menu[
"topic"] >> topic_name;
41 text = single_menu[
"text"].as<std::string>();
42 topic_name = single_menu[
"topic"].as<std::string>();
44 ROS_INFO(
"Regist %s, %s",
text.c_str(), topic_name.c_str());
51 std_msgs::String text_msg;
52 text_msg.data = feedback->marker_name;