moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | Protected Attributes | List of all members
moveit_setup::DataWarehouse Class Reference

Container for all of the SetupConfig object singletons. More...

#include <data_warehouse.hpp>

Inheritance diagram for moveit_setup::DataWarehouse:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::DataWarehouse:
Collaboration graph
[legend]

Public Member Functions

 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...
 

Public Attributes

bool debug { false }
 Is this application in debug mode? More...
 

Protected Attributes

rclcpp::Node::SharedPtr parent_node_
 
pluginlib::ClassLoader< SetupConfigconfig_loader_
 
std::unordered_map< std::string, SetupConfigPtr > configs_
 
std::unordered_map< std::string, std::string > registered_types_
 
std::vector< std::string > registered_names_
 

Detailed Description

Container for all of the SetupConfig object singletons.

Definition at line 52 of file data_warehouse.hpp.

Constructor & Destructor Documentation

◆ DataWarehouse()

moveit_setup::DataWarehouse::DataWarehouse ( const rclcpp::Node::SharedPtr &  parent_node)

Definition at line 44 of file data_warehouse.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ 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_nameThe name of the SetupConfig
config_classThe string used to load the class via pluginlib. If empty, the registered type is used.
Exceptions
std::runtime_errorIf 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.

Here is the call graph for this function:

◆ 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_nameThe name of the SetupConfig
config_classThe string used to load the class via pluginlib. If empty, the registered type is used.
Exceptions
std::runtime_errorIf 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.

Here is the caller graph for this function:

◆ 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_classThe 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.

Here is the call graph for this function:

◆ getConfigured()

std::vector< SetupConfigPtr > moveit_setup::DataWarehouse::getConfigured ( )

Returns a list of the SetupConfig for which isConfigured is true.

Definition at line 90 of file data_warehouse.cpp.

◆ 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)

Definition at line 57 of file data_warehouse.cpp.

◆ preloadWithURDFPath()

void moveit_setup::DataWarehouse::preloadWithURDFPath ( const std::filesystem::path &  urdf_path)

Definition at line 52 of file data_warehouse.cpp.

◆ 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.

Here is the caller graph for this function:

Member Data Documentation

◆ config_loader_

pluginlib::ClassLoader<SetupConfig> moveit_setup::DataWarehouse::config_loader_
protected

Definition at line 131 of file data_warehouse.hpp.

◆ configs_

std::unordered_map<std::string, SetupConfigPtr> moveit_setup::DataWarehouse::configs_
protected

Definition at line 132 of file data_warehouse.hpp.

◆ debug

bool moveit_setup::DataWarehouse::debug { false }

Is this application in debug mode?

Definition at line 127 of file data_warehouse.hpp.

◆ parent_node_

rclcpp::Node::SharedPtr moveit_setup::DataWarehouse::parent_node_
protected

Definition at line 130 of file data_warehouse.hpp.

◆ registered_names_

std::vector<std::string> moveit_setup::DataWarehouse::registered_names_
protected

Definition at line 134 of file data_warehouse.hpp.

◆ registered_types_

std::unordered_map<std::string, std::string> moveit_setup::DataWarehouse::registered_types_
protected

Definition at line 133 of file data_warehouse.hpp.


The documentation for this class was generated from the following files: