moveit2
The MoveIt Motion Planning Framework for ROS 2.
urdf_config.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik Robotics, 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 PickNik Robotics 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 
38 #include <boost/algorithm/string/join.hpp>
39 
40 namespace moveit_setup
41 {
43 {
44  parent_node_->declare_parameter("robot_description", rclcpp::ParameterType::PARAMETER_STRING);
45 }
46 
47 void URDFConfig::loadPrevious(const std::filesystem::path& /*config_package_path*/, const YAML::Node& node)
48 {
49  if (!getYamlProperty(node, "package", urdf_pkg_name_))
50  {
51  throw std::runtime_error("cannot find package property in URDF");
52  }
53 
54  if (!getYamlProperty(node, "relative_path", urdf_pkg_relative_path_))
55  {
56  throw std::runtime_error("cannot find relative_path property in URDF");
57  }
58 
59  getYamlProperty(node, "xacro_args", xacro_args_);
61 }
62 
63 YAML::Node URDFConfig::saveToYaml() const
64 {
65  YAML::Node node;
66  node["package"] = urdf_pkg_name_;
67  node["relative_path"] = urdf_pkg_relative_path_.string();
68  if (!xacro_args_.empty())
69  {
70  node["xacro_args"] = xacro_args_;
71  }
72  return node;
73 }
74 
75 void URDFConfig::loadFromPath(const std::filesystem::path& urdf_file_path, const std::string& xacro_args)
76 {
77  urdf_path_ = urdf_file_path;
78  xacro_args_ = xacro_args;
81  load();
82 }
83 
84 void URDFConfig::loadFromPath(const std::filesystem::path& urdf_file_path, const std::vector<std::string>& xacro_args)
85 {
86  urdf_path_ = urdf_file_path;
87  xacro_args_vec_ = xacro_args;
88  xacro_args_ = boost::algorithm::join(xacro_args_vec_, " ");
90  load();
91 }
92 
94 {
96  if (!package_found)
97  {
98  urdf_pkg_name_ = "";
99  urdf_pkg_relative_path_ = urdf_path_; // just the absolute path
100  }
101  else
102  {
103  // Check that ROS can find the package
104  const std::filesystem::path robot_desc_pkg_path = getSharePath(urdf_pkg_name_);
105 
106  if (robot_desc_pkg_path.empty())
107  {
108  RCLCPP_WARN(*logger_,
109  "Package Not Found In ROS Workspace. ROS was unable to find the package name '%s'"
110  " within the ROS workspace. This may cause issues later.",
111  urdf_pkg_name_.c_str());
112  }
113  }
114 }
115 
116 void URDFConfig::loadFromPackage(const std::filesystem::path& package_name, const std::filesystem::path& relative_path,
117  const std::string& xacro_args)
118 {
119  const std::filesystem::path package_path = getSharePath(package_name.string());
120  if (package_path.empty())
121  {
122  throw std::runtime_error("URDF/COLLADA package not found: ''" + package_name.string());
123  }
124 
125  urdf_pkg_name_ = package_name.string();
126  urdf_pkg_relative_path_ = relative_path;
127  xacro_args_ = xacro_args;
128 
129  urdf_path_ = getSharePath(urdf_pkg_name_) / relative_path;
130  load();
131 }
132 
134 {
135  RCLCPP_DEBUG_STREAM(*logger_, "URDF Package Name: " << urdf_pkg_name_);
136  RCLCPP_DEBUG_STREAM(*logger_, "URDF Package Path: " << urdf_pkg_relative_path_);
137 
139  {
140  throw std::runtime_error("URDF/COLLADA file not found: " + urdf_path_.string());
141  }
142 
144  {
145  throw std::runtime_error("Running xacro failed.\nPlease check console for errors.");
146  }
147 
148  // Verify that file is in correct format / not an XACRO by loading into robot model
149  if (!urdf_model_->initString(urdf_string_))
150  {
151  throw std::runtime_error("URDF/COLLADA file is not a valid robot model.");
152  }
154 
155  // Set parameter
156  parent_node_->set_parameter(rclcpp::Parameter("robot_description", urdf_string_));
157 
158  RCLCPP_INFO_STREAM(*logger_, "Loaded " << urdf_model_->getName() << " robot model.");
159 }
160 
162 {
164 }
165 
167 {
168  return urdf_model_->getRoot() != nullptr;
169 }
170 
171 void URDFConfig::collectDependencies(std::set<std::string>& packages) const
172 {
173  packages.insert(urdf_pkg_name_);
174 }
175 
176 void URDFConfig::collectVariables(std::vector<TemplateVariable>& variables)
177 {
178  std::string urdf_location;
179  if (urdf_pkg_name_.empty())
180  {
181  urdf_location = urdf_path_.string();
182  }
183  else
184  {
185  urdf_location = "$(find " + urdf_pkg_name_ + ")/" + urdf_pkg_relative_path_.string();
186  }
187 
188  variables.push_back(TemplateVariable("URDF_LOCATION", urdf_location));
189 
190  if (urdf_from_xacro_)
191  {
192  variables.push_back(
193  TemplateVariable("URDF_LOAD_ATTRIBUTE", "command=\"xacro " + xacro_args_ + " '" + urdf_location + "'\""));
194  }
195  else
196  {
197  variables.push_back(TemplateVariable("URDF_LOAD_ATTRIBUTE", "textfile=\"" + urdf_location + "\""));
198  }
199 }
200 } // namespace moveit_setup
201 
202 #include <pluginlib/class_list_macros.hpp> // NOLINT
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
where all the data for each part of the configuration is stored.
Definition: config.hpp:58
rclcpp::Node::SharedPtr parent_node_
Definition: config.hpp:162
std::shared_ptr< rclcpp::Logger > logger_
Definition: config.hpp:164
void collectDependencies(std::set< std::string > &packages) const override
Collect the package dependencies generated by this configuration.
std::filesystem::path urdf_path_
Full file-system path to urdf.
void loadFromPath(const std::filesystem::path &urdf_file_path, const std::string &xacro_args="")
Load URDF File.
Definition: urdf_config.cpp:75
std::filesystem::path urdf_pkg_relative_path_
Path relative to urdf package (note: this may be same as urdf_path_)
YAML::Node saveToYaml() const override
Optionally save "meta" information for saving in the .setup_assistant yaml file.
Definition: urdf_config.cpp:63
bool isConfigured() const override
Return true if this part of the configuration is completely set up.
void loadFromPackage(const std::filesystem::path &package_name, const std::filesystem::path &relative_path, const std::string &xacro_args="")
std::vector< std::string > xacro_args_vec_
bool urdf_from_xacro_
Flag indicating whether the URDF was loaded from .xacro format.
std::shared_ptr< urdf::Model > urdf_model_
URDF robot model.
void onInit() override
Overridable initialization method.
Definition: urdf_config.cpp:42
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
Definition: urdf_config.cpp:47
std::string xacro_args_
xacro arguments in two different formats
void collectVariables(std::vector< TemplateVariable > &variables) override
Collect key/value pairs for use in templates.
std::string urdf_string_
URDF robot model string.
std::string urdf_pkg_name_
Name of package containing urdf (note: this may be empty b/c user may not have urdf in pkg)
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
bool getYamlProperty(const YAML::Node &node, const std::string &key, T &storage, const T &default_value=T())
Definition: utilities.hpp:110
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
Definition: utilities.hpp:50
bool extractPackageNameFromPath(const std::filesystem::path &path, std::string &package_name, std::filesystem::path &relative_filepath)
Definition: utilities.cpp:41
string package_name
Definition: setup.py:4
packages
Definition: setup.py:9
Simple Key/value pair for templates.
Definition: templates.hpp:47