rdf_loader.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Mathias Lüdtke, Dave Coleman */
36 
37 // MoveIt
40 
41 // ROS
42 #include <ros/ros.h>
43 #include <ros/package.h>
44 
45 // Boost
46 #include <boost/filesystem.hpp>
47 
48 // C++
49 #include <fstream>
50 #include <streambuf>
51 #include <algorithm>
52 
53 #ifdef _WIN32
54 #define popen _popen
55 #define pclose _pclose
56 #endif
57 
58 rdf_loader::RDFLoader::RDFLoader(const std::string& robot_description)
59 {
61  moveit::tools::Profiler::ScopedBlock prof_block("RDFLoader(robot_description)");
62 
64  ros::NodeHandle nh("~");
65  std::string content;
66 
67  if (!nh.searchParam(robot_description, robot_description_) || !nh.getParam(robot_description_, content))
68  {
69  ROS_ERROR_NAMED("rdf_loader", "Robot model parameter not found! Did you remap '%s'?", robot_description.c_str());
70  return;
71  }
72 
73  std::unique_ptr<urdf::Model> urdf(new urdf::Model());
74  if (!urdf->initString(content))
75  {
76  ROS_ERROR_NAMED("rdf_loader", "Unable to parse URDF from parameter '%s'", robot_description_.c_str());
77  return;
78  }
79  urdf_ = std::move(urdf);
80 
81  const std::string srdf_description(robot_description_ + "_semantic");
82  std::string scontent;
83  if (!nh.getParam(srdf_description, scontent))
84  {
85  ROS_ERROR_NAMED("rdf_loader", "Robot semantic description not found. Did you forget to define or remap '%s'?",
86  srdf_description.c_str());
87  return;
88  }
89 
90  auto srdf = std::make_shared<srdf::Model>();
91  if (!srdf->initString(*urdf_, scontent))
92  {
93  ROS_ERROR_NAMED("rdf_loader", "Unable to parse SRDF from parameter '%s'", srdf_description.c_str());
94  return;
95  }
96  srdf_ = std::move(srdf);
97 
98  ROS_DEBUG_STREAM_NAMED("rdf", "Loaded robot model in " << (ros::WallTime::now() - start).toSec() << " seconds");
99 }
100 
101 rdf_loader::RDFLoader::RDFLoader(const std::string& urdf_string, const std::string& srdf_string)
102 {
104  moveit::tools::Profiler::ScopedBlock prof_block("RDFLoader(string)");
105 
106  auto umodel = std::make_unique<urdf::Model>();
107  if (umodel->initString(urdf_string))
108  {
109  auto smodel = std::make_shared<srdf::Model>();
110  if (!smodel->initString(*umodel, srdf_string))
111  {
112  ROS_ERROR_NAMED("rdf_loader", "Unable to parse SRDF");
113  }
114  urdf_ = std::move(umodel);
115  srdf_ = std::move(smodel);
116  }
117  else
118  {
119  ROS_ERROR_NAMED("rdf_loader", "Unable to parse URDF");
120  }
121 }
122 
123 bool rdf_loader::RDFLoader::isXacroFile(const std::string& path)
124 {
125  std::string lower_path = path;
126  std::transform(lower_path.begin(), lower_path.end(), lower_path.begin(), ::tolower);
127 
128  return lower_path.find(".xacro") != std::string::npos;
129 }
130 
131 bool rdf_loader::RDFLoader::loadFileToString(std::string& buffer, const std::string& path)
132 {
133  if (path.empty())
134  {
135  ROS_ERROR_NAMED("rdf_loader", "Path is empty");
136  return false;
137  }
138 
139  if (!boost::filesystem::exists(path))
140  {
141  ROS_ERROR_NAMED("rdf_loader", "File does not exist");
142  return false;
143  }
144 
145  std::ifstream stream(path.c_str());
146  if (!stream.good())
147  {
148  ROS_ERROR_NAMED("rdf_loader", "Unable to load path");
149  return false;
150  }
151 
152  // Load the file to a string using an efficient memory allocation technique
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>());
157  stream.close();
158 
159  return true;
160 }
161 
162 bool rdf_loader::RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& path,
163  const std::vector<std::string>& xacro_args)
164 {
165  buffer.clear();
166  if (path.empty())
167  {
168  ROS_ERROR_NAMED("rdf_loader", "Path is empty");
169  return false;
170  }
171 
172  if (!boost::filesystem::exists(path))
173  {
174  ROS_ERROR_NAMED("rdf_loader", "File does not exist");
175  return false;
176  }
177 
178  std::string cmd = "rosrun xacro xacro ";
179  for (const std::string& xacro_arg : xacro_args)
180  cmd += xacro_arg + " ";
181  cmd += path;
182 
183  FILE* pipe = popen(cmd.c_str(), "r");
184  if (!pipe)
185  {
186  ROS_ERROR_NAMED("rdf_loader", "Unable to load path");
187  return false;
188  }
189 
190  char pipe_buffer[128];
191  while (!feof(pipe))
192  {
193  if (fgets(pipe_buffer, 128, pipe) != nullptr)
194  buffer += pipe_buffer;
195  }
196  pclose(pipe);
197 
198  return true;
199 }
200 
201 bool rdf_loader::RDFLoader::loadXmlFileToString(std::string& buffer, const std::string& path,
202  const std::vector<std::string>& xacro_args)
203 {
204  if (isXacroFile(path))
205  {
206  return loadXacroFileToString(buffer, path, xacro_args);
207  }
208 
209  return loadFileToString(buffer, path);
210 }
211 
212 bool rdf_loader::RDFLoader::loadPkgFileToString(std::string& buffer, const std::string& package_name,
213  const std::string& relative_path,
214  const std::vector<std::string>& xacro_args)
215 {
216  std::string package_path = ros::package::getPath(package_name);
217 
218  if (package_path.empty())
219  {
220  ROS_ERROR_STREAM_NAMED("rdf_loader", "ROS was unable to find the package name '" << package_name << "'");
221  return false;
222  }
223 
224  boost::filesystem::path path(package_path);
225  // Use boost to cross-platform combine paths
226  path = path / relative_path;
227 
228  return loadXmlFileToString(buffer, path.string(), xacro_args);
229 }
rdf_loader::RDFLoader::loadFileToString
static bool loadFileToString(std::string &buffer, const std::string &path)
load file from given path into buffer
Definition: rdf_loader.cpp:131
rdf_loader::RDFLoader::loadPkgFileToString
static bool loadPkgFileToString(std::string &buffer, const std::string &package_name, const std::string &relative_path, const std::vector< std::string > &xacro_args)
helper that generates a file path based on package name and relative file path to package
Definition: rdf_loader.cpp:212
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
rdf_loader::RDFLoader::srdf_
srdf::ModelSharedPtr srdf_
Definition: rdf_loader.h:130
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
rdf_loader::RDFLoader::loadXacroFileToString
static bool loadXacroFileToString(std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args)
run xacro with the given args on the file, return result in buffer
Definition: rdf_loader.cpp:162
moveit::tools::Profiler::ScopedStart
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
urdf::Model
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
rdf_loader::RDFLoader::urdf_
urdf::ModelInterfaceSharedPtr urdf_
Definition: rdf_loader.h:131
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
rdf_loader::RDFLoader::isXacroFile
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
Definition: rdf_loader.cpp:123
ros::WallTime
package.h
start
ROSCPP_DECL void start()
urdf
rdf_loader::RDFLoader::loadXmlFileToString
static bool loadXmlFileToString(std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args)
helper that branches between loadFileToString() and loadXacroFileToString() based on result of isXacr...
Definition: rdf_loader.cpp:201
srdf
moveit::tools::Profiler::ScopedBlock
rdf_loader::RDFLoader::RDFLoader
RDFLoader(const std::string &robot_description="robot_description")
Default constructor.
Definition: rdf_loader.cpp:58
profiler.h
cmd
string cmd
rdf_loader::RDFLoader::robot_description_
std::string robot_description_
Definition: rdf_loader.h:129
rdf_loader.h
ros::NodeHandle


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Feb 21 2024 03:25:45