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

where all the data for each part of the configuration is stored. More...

#include <config.hpp>

Inheritance diagram for moveit_setup::SetupConfig:
Inheritance graph
[legend]

Public Member Functions

 SetupConfig ()=default
 
 SetupConfig (const SetupConfig &)=default
 
 SetupConfig (SetupConfig &&)=default
 
SetupConfigoperator= (const SetupConfig &)=default
 
SetupConfigoperator= (SetupConfig &&)=default
 
virtual ~SetupConfig ()=default
 
void initialize (const std::shared_ptr< DataWarehouse > &config_data, const rclcpp::Node::SharedPtr &parent_node, const std::string &name)
 Called after construction to initialize the step. More...
 
virtual void onInit ()
 Overridable initialization method. More...
 
const std::string & getName ()
 The name for this part of the configuration. More...
 
virtual bool isConfigured () const
 Return true if this part of the configuration is completely set up. More...
 
virtual void loadPrevious (const std::filesystem::path &, const YAML::Node &)
 Loads the configuration from an existing MoveIt configuration. More...
 
virtual YAML::Node saveToYaml () const
 Optionally save "meta" information for saving in the .setup_assistant yaml file. More...
 
virtual void collectFiles (const std::filesystem::path &, const GeneratedTime &, std::vector< GeneratedFilePtr > &)
 Collect the files generated by this configuration and add them to the vector. More...
 
virtual void collectDependencies (std::set< std::string > &) const
 Collect the package dependencies generated by this configuration. More...
 
virtual void collectVariables (std::vector< TemplateVariable > &)
 Collect key/value pairs for use in templates. More...
 

Protected Attributes

std::shared_ptr< DataWarehouseconfig_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::string name_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

where all the data for each part of the configuration is stored.

Definition at line 57 of file config.hpp.

Constructor & Destructor Documentation

◆ SetupConfig() [1/3]

moveit_setup::SetupConfig::SetupConfig ( )
default

◆ SetupConfig() [2/3]

moveit_setup::SetupConfig::SetupConfig ( const SetupConfig )
default

◆ SetupConfig() [3/3]

moveit_setup::SetupConfig::SetupConfig ( SetupConfig &&  )
default

◆ ~SetupConfig()

virtual moveit_setup::SetupConfig::~SetupConfig ( )
virtualdefault

Member Function Documentation

◆ collectDependencies()

virtual void moveit_setup::SetupConfig::collectDependencies ( std::set< std::string > &  ) const
inlinevirtual

Collect the package dependencies generated by this configuration.

Parameters
[out]packagesNames of ROS packages

Reimplemented in moveit_setup::URDFConfig, moveit_setup::ModifiedUrdfConfig, and moveit_setup::app::LaunchesConfig.

Definition at line 147 of file config.hpp.

◆ collectFiles()

virtual void moveit_setup::SetupConfig::collectFiles ( const std::filesystem::path &  ,
const GeneratedTime ,
std::vector< GeneratedFilePtr > &   
)
inlinevirtual

Collect the files generated by this configuration and add them to the vector.

Parameters
[in]package_paththe path to the root of the config package
[in]last_gen_timeThe time (if any) when the config package was last generated @parma[out] files Where to put the new generated files

Reimplemented in moveit_setup::srdf_setup::GroupMetaConfig, moveit_setup::SRDFConfig, moveit_setup::PackageSettingsConfig, moveit_setup::controllers::ROS2ControllersConfig, moveit_setup::controllers::MoveItControllersConfig, moveit_setup::ModifiedUrdfConfig, moveit_setup::controllers::ControlXacroConfig, moveit_setup::app::PerceptionConfig, and moveit_setup::app::LaunchesConfig.

Definition at line 137 of file config.hpp.

◆ collectVariables()

virtual void moveit_setup::SetupConfig::collectVariables ( std::vector< TemplateVariable > &  )
inlinevirtual

Collect key/value pairs for use in templates.

Parameters
[out]variablesWhere to put the new Variables

Reimplemented in moveit_setup::srdf_setup::GroupMetaConfig, moveit_setup::URDFConfig, moveit_setup::SRDFConfig, moveit_setup::PackageSettingsConfig, moveit_setup::ModifiedUrdfConfig, and moveit_setup::controllers::ControlXacroConfig.

Definition at line 156 of file config.hpp.

◆ getName()

const std::string& moveit_setup::SetupConfig::getName ( )
inline

The name for this part of the configuration.

Definition at line 93 of file config.hpp.

◆ initialize()

void moveit_setup::SetupConfig::initialize ( const std::shared_ptr< DataWarehouse > &  config_data,
const rclcpp::Node::SharedPtr &  parent_node,
const std::string &  name 
)
inline

Called after construction to initialize the step.

Parameters
config_dataPointer to all the other configs
parent_nodeShared pointer to the parent node
name

Definition at line 73 of file config.hpp.

Here is the call graph for this function:

◆ isConfigured()

virtual bool moveit_setup::SetupConfig::isConfigured ( ) const
inlinevirtual

◆ loadPrevious()

virtual void moveit_setup::SetupConfig::loadPrevious ( const std::filesystem::path &  ,
const YAML::Node &   
)
inlinevirtual

Loads the configuration from an existing MoveIt configuration.

The data can be loaded directly from files in the configuration via the package path.

Certain other pieces of "meta" information may be stored in the .setup_assistant yaml file in the root of the configuration. If there is a node in that file that matches this config's name, it is passed in as an argument.

Parameters
package_pathThe path to the root folder of the configuration.

Reimplemented in moveit_setup::srdf_setup::GroupMetaConfig, moveit_setup::URDFConfig, moveit_setup::SRDFConfig, moveit_setup::PackageSettingsConfig, moveit_setup::controllers::ROS2ControllersConfig, moveit_setup::controllers::MoveItControllersConfig, moveit_setup::app::PerceptionConfig, moveit_setup::ModifiedUrdfConfig, and moveit_setup::controllers::ControlXacroConfig.

Definition at line 118 of file config.hpp.

◆ onInit()

virtual void moveit_setup::SetupConfig::onInit ( )
inlinevirtual

◆ operator=() [1/2]

SetupConfig& moveit_setup::SetupConfig::operator= ( const SetupConfig )
default

◆ operator=() [2/2]

SetupConfig& moveit_setup::SetupConfig::operator= ( SetupConfig &&  )
default

◆ saveToYaml()

virtual YAML::Node moveit_setup::SetupConfig::saveToYaml ( ) const
inlinevirtual

Optionally save "meta" information for saving in the .setup_assistant yaml file.

Reimplemented in moveit_setup::URDFConfig, moveit_setup::SRDFConfig, moveit_setup::PackageSettingsConfig, moveit_setup::ModifiedUrdfConfig, and moveit_setup::controllers::ControlXacroConfig.

Definition at line 125 of file config.hpp.

Member Data Documentation

◆ config_data_

std::shared_ptr<DataWarehouse> moveit_setup::SetupConfig::config_data_
protected

Definition at line 161 of file config.hpp.

◆ logger_

std::shared_ptr<rclcpp::Logger> moveit_setup::SetupConfig::logger_
protected

Definition at line 164 of file config.hpp.

◆ name_

std::string moveit_setup::SetupConfig::name_
protected

Definition at line 163 of file config.hpp.

◆ parent_node_

rclcpp::Node::SharedPtr moveit_setup::SetupConfig::parent_node_
protected

Definition at line 162 of file config.hpp.


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