38 #include <boost/algorithm/string/join.hpp> 
   44   parent_node_->declare_parameter(
"robot_description", rclcpp::ParameterType::PARAMETER_STRING);
 
   51     throw std::runtime_error(
"cannot find package property in URDF");
 
   56     throw std::runtime_error(
"cannot find relative_path property in URDF");
 
  106     if (robot_desc_pkg_path.empty())
 
  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.",
 
  117                                  const std::string& xacro_args)
 
  120   if (package_path.empty())
 
  122     throw std::runtime_error(
"URDF/COLLADA package not found: ''" + 
package_name.string());
 
  140     throw std::runtime_error(
"URDF/COLLADA file not found: " + 
urdf_path_.string());
 
  145     throw std::runtime_error(
"Running xacro failed.\nPlease check console for errors.");
 
  151     throw std::runtime_error(
"URDF/COLLADA file is not a valid robot model.");
 
  178   std::string urdf_location;
 
  197     variables.push_back(
TemplateVariable(
"URDF_LOAD_ATTRIBUTE", 
"textfile=\"" + urdf_location + 
"\""));
 
  202 #include <pluginlib/class_list_macros.hpp>   
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.
 
rclcpp::Node::SharedPtr parent_node_
 
std::shared_ptr< rclcpp::Logger > logger_
 
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.
 
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.
 
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.
 
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
 
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...
 
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
 
bool getYamlProperty(const YAML::Node &node, const std::string &key, T &storage, const T &default_value=T())
 
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
 
bool extractPackageNameFromPath(const std::filesystem::path &path, std::string &package_name, std::filesystem::path &relative_filepath)
 
Simple Key/value pair for templates.