45 : parent_node_(parent_node), config_loader_(
"moveit_setup_framework",
"moveit_setup::SetupConfig")
49 registerType(
"package_settings",
"moveit_setup::PackageSettingsConfig");
54 get<URDFConfig>(
"urdf")->loadFromPath(urdf_path);
59 get<PackageSettingsConfig>(
"package_settings")->loadExisting(package_path_or_name);
64 if (config_class.empty())
69 throw std::runtime_error(config_name +
" does not have a registered type in the data warehouse");
71 config_class = it->second;
73 auto it =
configs_.find(config_name);
79 config->initialize(shared_from_this(),
parent_node_, config_name);
92 std::vector<SetupConfigPtr> configs;
95 auto it =
configs_.find(config_name);
100 SetupConfigPtr ptr = it->second;
101 if (ptr->isConfigured())
103 configs.push_back(ptr);
void preloadWithFullConfig(const std::string &package_path_or_name)
SetupConfigPtr get(const std::string &config_name, std::string config_class="")
Get the singleton for a given config name and class.
std::unordered_map< std::string, std::string > registered_types_
const std::vector< std::string > & getRegisteredNames() const
Returns a list of config_names that have registered types associated with them.
pluginlib::ClassLoader< SetupConfig > config_loader_
std::vector< std::string > registered_names_
DataWarehouse(const rclcpp::Node::SharedPtr &parent_node)
std::unordered_map< std::string, SetupConfigPtr > configs_
rclcpp::Node::SharedPtr parent_node_
std::vector< SetupConfigPtr > getConfigured()
Returns a list of the SetupConfig for which isConfigured is true.
void preloadWithURDFPath(const std::filesystem::path &urdf_path)
void registerType(const std::string &config_name, const std::string &config_class)
Associates a class_name with the given name. Makes calls to get more succinct.