Container for all of the SetupConfig
object singletons.
More...
#include <data_warehouse.hpp>
|
| DataWarehouse (const rclcpp::Node::SharedPtr &parent_node) |
|
void | preloadWithURDFPath (const std::filesystem::path &urdf_path) |
|
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. More...
|
|
template<typename T > |
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. More...
|
|
template<typename T > |
std::unordered_map< std::string, std::shared_ptr< T > > | getAll () |
| Get all of the registered configs that match the given config_class. More...
|
|
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. More...
|
|
std::vector< SetupConfigPtr > | getConfigured () |
| Returns a list of the SetupConfig for which isConfigured is true. More...
|
|
const std::vector< std::string > & | getRegisteredNames () const |
| Returns a list of config_names that have registered types associated with them. More...
|
|
|
bool | debug { false } |
| Is this application in debug mode? More...
|
|
Container for all of the SetupConfig
object singletons.
Definition at line 52 of file data_warehouse.hpp.
◆ DataWarehouse()
moveit_setup::DataWarehouse::DataWarehouse |
( |
const rclcpp::Node::SharedPtr & |
parent_node | ) |
|
◆ get() [1/2]
template<typename T >
std::shared_ptr<T> moveit_setup::DataWarehouse::get |
( |
const std::string & |
config_name, |
|
|
const std::string & |
config_class = "" |
|
) |
| |
|
inline |
Get the specific singleton for a given config name and class.
Unlike the non-templated version of this method, this returns the SetupConfig pointer cast to the specific config type.
- Parameters
-
config_name | The name of the SetupConfig |
config_class | The string used to load the class via pluginlib. If empty, the registered type is used. |
- Exceptions
-
std::runtime_error | If the name is not registered to a type |
- Returns
- Shared pointer to the specific SetupConfig object
Definition at line 82 of file data_warehouse.hpp.
◆ get() [2/2]
SetupConfigPtr moveit_setup::DataWarehouse::get |
( |
const std::string & |
config_name, |
|
|
std::string |
config_class = "" |
|
) |
| |
Get the singleton for a given config name and class.
- Parameters
-
config_name | The name of the SetupConfig |
config_class | The string used to load the class via pluginlib. If empty, the registered type is used. |
- Exceptions
-
std::runtime_error | If the name is not registered to a type |
- Returns
- Shared pointer to the generic SetupConfig object
Definition at line 62 of file data_warehouse.cpp.
◆ getAll()
template<typename T >
std::unordered_map<std::string, std::shared_ptr<T> > moveit_setup::DataWarehouse::getAll |
( |
| ) |
|
|
inline |
Get all of the registered configs that match the given config_class.
- Parameters
-
config_class | The string representing the class name |
- Returns
- Map of shared pointers from config names to singleton config
Definition at line 94 of file data_warehouse.hpp.
◆ getConfigured()
std::vector< SetupConfigPtr > moveit_setup::DataWarehouse::getConfigured |
( |
| ) |
|
◆ getRegisteredNames()
const std::vector< std::string > & moveit_setup::DataWarehouse::getRegisteredNames |
( |
| ) |
const |
Returns a list of config_names that have registered types associated with them.
Definition at line 109 of file data_warehouse.cpp.
◆ preloadWithFullConfig()
void moveit_setup::DataWarehouse::preloadWithFullConfig |
( |
const std::string & |
package_path_or_name | ) |
|
◆ preloadWithURDFPath()
void moveit_setup::DataWarehouse::preloadWithURDFPath |
( |
const std::filesystem::path & |
urdf_path | ) |
|
◆ registerType()
void moveit_setup::DataWarehouse::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.
Definition at line 84 of file data_warehouse.cpp.
◆ config_loader_
pluginlib::ClassLoader<SetupConfig> moveit_setup::DataWarehouse::config_loader_ |
|
protected |
◆ configs_
std::unordered_map<std::string, SetupConfigPtr> moveit_setup::DataWarehouse::configs_ |
|
protected |
◆ debug
bool moveit_setup::DataWarehouse::debug { false } |
◆ parent_node_
rclcpp::Node::SharedPtr moveit_setup::DataWarehouse::parent_node_ |
|
protected |
◆ registered_names_
std::vector<std::string> moveit_setup::DataWarehouse::registered_names_ |
|
protected |
◆ registered_types_
std::unordered_map<std::string, std::string> moveit_setup::DataWarehouse::registered_types_ |
|
protected |
The documentation for this class was generated from the following files: