46 #include <boost/filesystem.hpp>
55 #define pclose _pclose
69 ROS_ERROR_NAMED(
"rdf_loader",
"Robot model parameter not found! Did you remap '%s'?", robot_description.c_str());
74 if (!
urdf->initString(content))
83 if (!nh.
getParam(srdf_description, scontent))
85 ROS_ERROR_NAMED(
"rdf_loader",
"Robot semantic description not found. Did you forget to define or remap '%s'?",
86 srdf_description.c_str());
90 auto srdf = std::make_shared<srdf::Model>();
93 ROS_ERROR_NAMED(
"rdf_loader",
"Unable to parse SRDF from parameter '%s'", srdf_description.c_str());
106 auto umodel = std::make_unique<urdf::Model>();
107 if (umodel->initString(urdf_string))
109 auto smodel = std::make_shared<srdf::Model>();
110 if (!smodel->initString(*umodel, srdf_string))
114 urdf_ = std::move(umodel);
115 srdf_ = std::move(smodel);
125 std::string lower_path = path;
126 std::transform(lower_path.begin(), lower_path.end(), lower_path.begin(), ::tolower);
128 return lower_path.find(
".xacro") != std::string::npos;
139 if (!boost::filesystem::exists(path))
145 std::ifstream stream(path.c_str());
153 stream.seekg(0, std::ios::end);
154 buffer.reserve(stream.tellg());
155 stream.seekg(0, std::ios::beg);
156 buffer.assign((std::istreambuf_iterator<char>(stream)), std::istreambuf_iterator<char>());
163 const std::vector<std::string>& xacro_args)
172 if (!boost::filesystem::exists(path))
178 std::string
cmd =
"rosrun xacro xacro ";
179 for (
const std::string& xacro_arg : xacro_args)
180 cmd += xacro_arg +
" ";
183 FILE* pipe = popen(
cmd.c_str(),
"r");
190 char pipe_buffer[128];
193 if (fgets(pipe_buffer, 128, pipe) !=
nullptr)
194 buffer += pipe_buffer;
202 const std::vector<std::string>& xacro_args)
204 if (isXacroFile(path))
206 return loadXacroFileToString(buffer, path, xacro_args);
209 return loadFileToString(buffer, path);
213 const std::string& relative_path,
214 const std::vector<std::string>& xacro_args)
218 if (package_path.empty())
224 boost::filesystem::path path(package_path);
226 path = path / relative_path;
228 return loadXmlFileToString(buffer, path.string(), xacro_args);