53   std::vector<std::string> xacro_names_vector;
 
   70   unsigned int count = 0;
 
   73     if (!pair.second->isConfigured())
 
   88                                       std::vector<GeneratedFilePtr>& files)
 
   90   files.push_back(std::make_shared<GeneratedModifiedURDF>(package_path, last_gen_time, *
this));
 
  103   std::string 
args = 
"", imports = 
"", commands = 
"";
 
  108     if (!xacro->isConfigured())
 
  112     for (
const std::pair<std::string, std::string>& argument : xacro->getArguments())
 
  114       args += 
"    <xacro:arg name=\"";
 
  115       args += argument.first;
 
  116       args += 
"\" default=\"";
 
  117       args += argument.second;
 
  121     imports += 
"    <!-- Import ";
 
  122     imports += pair.first;
 
  125     imports += 
"    <xacro:include filename=\"";
 
  126     imports += xacro->getFilepath();
 
  127     imports += 
"\" />\n\n";
 
  129     for (
const std::string& command : xacro->getCommands())
 
  143 #include <pluginlib/class_list_macros.hpp>   
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
 
std::shared_ptr< IncludedXacroConfig > Ptr
 
A configuration that stores info about modifications to the URDF.
 
void onInit() override
Overridable initialization method.
 
std::vector< IncludedXacroConfig::Ptr > getIncludedXacros() const
 
void collectDependencies(std::set< std::string > &packages) const override
Collect the package dependencies generated by this configuration.
 
void collectVariables(std::vector< TemplateVariable > &variables) override
Collect key/value pairs for use in templates.
 
YAML::Node saveToYaml() const override
Optionally save "meta" information for saving in the .setup_assistant yaml file.
 
std::vector< std::string > getIncludedXacroNames() const
 
bool isConfigured() const override
Return true if this part of the configuration is completely set up.
 
void loadPrevious(const std::filesystem::path &, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
 
std::shared_ptr< URDFConfig > urdf_config_
 
std::unordered_map< std::string, IncludedXacroConfig::Ptr > getIncludedXacroMap() const
 
void collectFiles(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, std::vector< GeneratedFilePtr > &files) override
Collect the files generated by this configuration and add them to the vector.
 
bool hasChanges() const
Returns true if this or any of the included xacros have changes, requiring the URDF to be regenerated...
 
std::set< std::string > cached_xacro_names_
 
where all the data for each part of the configuration is stored.
 
std::shared_ptr< DataWarehouse > config_data_
 
bool getYamlProperty(const YAML::Node &node, const std::string &key, T &storage, const T &default_value=T())
 
std::filesystem::file_time_type GeneratedTime
 
Simple Key/value pair for templates.