39 #include <pluginlib/class_loader.hpp> 
   40 #include <unordered_map> 
   52 class DataWarehouse : 
public std::enable_shared_from_this<DataWarehouse>
 
   68   SetupConfigPtr 
get(
const std::string& config_name, std::string config_class = 
"");
 
   82   std::shared_ptr<T> 
get(
const std::string& config_name, 
const std::string& config_class = 
"")
 
   84     return std::static_pointer_cast<T>(
get(config_name, config_class));
 
   94   std::unordered_map<std::string, std::shared_ptr<T>> 
getAll()
 
   96     std::unordered_map<std::string, std::shared_ptr<T>> matches;
 
   99       SetupConfigPtr uncast_ptr = 
get(pair.first);
 
  100       std::shared_ptr<T> ptr = std::dynamic_pointer_cast<T>(uncast_ptr);
 
  106       matches[pair.first] = ptr;
 
  114   void registerType(
const std::string& config_name, 
const std::string& config_class);
 
  132   std::unordered_map<std::string, SetupConfigPtr> 
configs_;        
 
Container for all of the SetupConfig object singletons.
 
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::shared_ptr< T > get(const std::string &config_name, const std::string &config_class="")
Get the specific singleton for a given config name and class.
 
std::unordered_map< std::string, std::shared_ptr< T > > getAll()
Get all of the registered configs that match the given config_class.
 
std::unordered_map< std::string, SetupConfigPtr > configs_
 
rclcpp::Node::SharedPtr parent_node_
 
bool debug
Is this application in debug mode?
 
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.
 
MOVEIT_CLASS_FORWARD(SetupConfig)