moveit2
The MoveIt Motion Planning Framework for ROS 2.
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
39 #include <std_msgs/msg/string.hpp>
40 #include <ament_index_cpp/get_package_prefix.hpp>
41 #include <ament_index_cpp/get_package_share_directory.hpp>
42 
43 #include <rclcpp/duration.hpp>
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <rclcpp/node.hpp>
47 #include <rclcpp/time.hpp>
48 
49 // C++
50 #include <fstream>
51 #include <streambuf>
52 #include <algorithm>
53 #include <chrono>
54 #include <filesystem>
55 
56 namespace rdf_loader
57 {
58 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_rdf_loader.rdf_loader");
59 
60 RDFLoader::RDFLoader(const std::shared_ptr<rclcpp::Node>& node, const std::string& ros_name,
61  bool default_continuous_value, double default_timeout)
62  : ros_name_(ros_name)
63 {
64  auto start = node->now();
65 
66  urdf_string_ = urdf_ssp_.loadInitialValue(
67  node, ros_name, [this](const std::string& new_urdf_string) { return urdfUpdateCallback(new_urdf_string); },
68  default_continuous_value, default_timeout);
69 
70  const std::string srdf_name = ros_name + "_semantic";
71  srdf_string_ = srdf_ssp_.loadInitialValue(
72  node, srdf_name, [this](const std::string& new_srdf_string) { return srdfUpdateCallback(new_srdf_string); },
73  default_continuous_value, default_timeout);
74 
75  if (!loadFromStrings())
76  {
77  return;
78  }
79 
80  RCLCPP_INFO_STREAM(LOGGER, "Loaded robot model in " << (node->now() - start).seconds() << " seconds");
81 }
82 
83 RDFLoader::RDFLoader(const std::string& urdf_string, const std::string& srdf_string)
84  : urdf_string_(urdf_string), srdf_string_(srdf_string)
85 {
86  if (!loadFromStrings())
87  {
88  return;
89  }
90 }
91 
92 bool RDFLoader::loadFromStrings()
93 {
94  std::unique_ptr<urdf::Model> urdf = std::make_unique<urdf::Model>();
95  if (!urdf->initString(urdf_string_))
96  {
97  RCLCPP_INFO(LOGGER, "Unable to parse URDF");
98  return false;
99  }
100 
101  srdf::ModelSharedPtr srdf = std::make_shared<srdf::Model>();
102  if (!srdf->initString(*urdf, srdf_string_))
103  {
104  RCLCPP_ERROR(LOGGER, "Unable to parse SRDF");
105  return false;
106  }
107 
108  urdf_ = std::move(urdf);
109  srdf_ = std::move(srdf);
110  return true;
111 }
112 
113 bool RDFLoader::isXacroFile(const std::string& path)
114 {
115  std::string lower_path = path;
116  std::transform(lower_path.begin(), lower_path.end(), lower_path.begin(), ::tolower);
117 
118  return lower_path.find(".xacro") != std::string::npos;
119 }
120 
121 bool RDFLoader::loadFileToString(std::string& buffer, const std::string& path)
122 {
123  if (path.empty())
124  {
125  RCLCPP_ERROR(LOGGER, "Path is empty");
126  return false;
127  }
128 
129  if (!std::filesystem::exists(path))
130  {
131  RCLCPP_ERROR(LOGGER, "File does not exist");
132  return false;
133  }
134 
135  std::ifstream stream(path.c_str());
136  if (!stream.good())
137  {
138  RCLCPP_ERROR(LOGGER, "Unable to load path");
139  return false;
140  }
141 
142  // Load the file to a string using an efficient memory allocation technique
143  stream.seekg(0, std::ios::end);
144  buffer.reserve(stream.tellg());
145  stream.seekg(0, std::ios::beg);
146  buffer.assign((std::istreambuf_iterator<char>(stream)), std::istreambuf_iterator<char>());
147  stream.close();
148 
149  return true;
150 }
151 
152 bool RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& path,
153  const std::vector<std::string>& xacro_args)
154 {
155  buffer.clear();
156  if (path.empty())
157  {
158  RCLCPP_ERROR(LOGGER, "Path is empty");
159  return false;
160  }
161 
162  if (!std::filesystem::exists(path))
163  {
164  RCLCPP_ERROR(LOGGER, "File does not exist");
165  return false;
166  }
167 
168  std::string cmd = "ros2 run xacro xacro ";
169  for (const std::string& xacro_arg : xacro_args)
170  cmd += xacro_arg + " ";
171  cmd += path;
172 
173 #ifdef _WIN32
174  FILE* pipe = _popen(cmd.c_str(), "r");
175 #else
176  FILE* pipe = popen(cmd.c_str(), "r");
177 #endif
178  if (!pipe)
179  {
180  RCLCPP_ERROR(LOGGER, "Unable to load path");
181  return false;
182  }
183 
184  char pipe_buffer[128];
185  while (!feof(pipe))
186  {
187  if (fgets(pipe_buffer, 128, pipe) != nullptr)
188  buffer += pipe_buffer;
189  }
190 #ifdef _WIN32
191  _pclose(pipe);
192 #else
193  pclose(pipe);
194 #endif
195 
196  return true;
197 }
198 
199 bool RDFLoader::loadXmlFileToString(std::string& buffer, const std::string& path,
200  const std::vector<std::string>& xacro_args)
201 {
202  if (isXacroFile(path))
203  {
204  return loadXacroFileToString(buffer, path, xacro_args);
205  }
206 
207  return loadFileToString(buffer, path);
208 }
209 
210 bool RDFLoader::loadPkgFileToString(std::string& buffer, const std::string& package_name,
211  const std::string& relative_path, const std::vector<std::string>& xacro_args)
212 {
213  std::string package_path;
214  try
215  {
217  }
218  catch (const ament_index_cpp::PackageNotFoundError& e)
219  {
220  RCLCPP_ERROR(LOGGER, "ament_index_cpp: %s", e.what());
221  return false;
222  }
223 
224  std::filesystem::path path(package_path);
225  path = path / relative_path;
226 
227  return loadXmlFileToString(buffer, path.string(), xacro_args);
228 }
229 
230 void RDFLoader::urdfUpdateCallback(const std::string& new_urdf_string)
231 {
232  urdf_string_ = new_urdf_string;
233  if (!loadFromStrings())
234  {
235  return;
236  }
237  if (new_model_cb_)
238  {
239  new_model_cb_();
240  }
241 }
242 
243 void RDFLoader::srdfUpdateCallback(const std::string& new_srdf_string)
244 {
245  srdf_string_ = new_srdf_string;
246  if (!loadFromStrings())
247  {
248  return;
249  }
250  if (new_model_cb_)
251  {
252  new_model_cb_();
253  }
254 }
255 } // namespace rdf_loader
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:199
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
Definition: rdf_loader.cpp:113
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:210
RDFLoader(const std::shared_ptr< rclcpp::Node > &node, const std::string &ros_name="robot_description", bool default_continuous_value=false, double default_timeout=10.0)
Default constructor.
Definition: rdf_loader.cpp:60
static bool loadFileToString(std::string &buffer, const std::string &path)
load file from given path into buffer
Definition: rdf_loader.cpp:121
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:152
std::string loadInitialValue(const std::shared_ptr< rclcpp::Node > &node, const std::string &name, const StringCallback &parent_callback={}, bool default_continuous_value=false, double default_timeout=10.0)
string package_name
Definition: setup.py:4
const rclcpp::Logger LOGGER
Definition: async_test.h:31