moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
moveit_setup::core::ConfigurationFiles Class Reference

#include <configuration_files.hpp>

Inheritance diagram for moveit_setup::core::ConfigurationFiles:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::core::ConfigurationFiles:
Collaboration graph
[legend]

Public Member Functions

std::string getName () const override
 Returns the name of the setup step.
 
void onInit () override
 Overridable initialization method.
 
const std::filesystem::path & getPackagePath ()
 
void setPackagePath (const std::filesystem::path &package_path)
 
void setPackageName (const std::string &package_name)
 
void loadFiles ()
 Populate the 'Files to be generated' list.
 
const std::vector< GeneratedFilePtr > getGeneratedFiles () const
 
unsigned int getNumFiles () const
 
bool shouldGenerate (const GeneratedFilePtr &file) const
 
bool hasModifiedFiles () const
 
bool hasConflictingFiles () const
 
void setShouldGenerate (const std::string &rel_path, bool should_generate)
 
bool isExistingConfig ()
 
bool hasSetupAssistantFile ()
 
void loadTemplateVariables ()
 
std::vector< std::string > getIncompleteWarnings () const
 
std::string getInvalidGroupName () const
 
void setGenerationTime ()
 
- Public Member Functions inherited from moveit_setup::SetupStep
 SetupStep ()=default
 
 SetupStep (const SetupStep &)=default
 
 SetupStep (SetupStep &&)=default
 
SetupStepoperator= (const SetupStep &)=default
 
SetupStepoperator= (SetupStep &&)=default
 
virtual ~SetupStep ()=default
 
void initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data)
 Called after construction to initialize the step.
 
virtual bool isReady () const
 Return true if the data necessary to proceed with this step has been configured.
 
const rclcpp::Logger & getLogger () const
 Makes a namespaced logger for this step available to the widget.
 

Protected Member Functions

bool hasMatchingFileStatus (FileStatus status) const
 

Protected Attributes

std::vector< GeneratedFilePtr > gen_files_
 Vector of all files to be generated.
 
std::unordered_map< std::string, bool > should_generate_
 
std::shared_ptr< PackageSettingsConfigpackage_settings_
 
- Protected Attributes inherited from moveit_setup::SetupStep
DataWarehousePtr config_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

Definition at line 43 of file configuration_files.hpp.

Member Function Documentation

◆ getGeneratedFiles()

const std::vector< GeneratedFilePtr > moveit_setup::core::ConfigurationFiles::getGeneratedFiles ( ) const
inline

Definition at line 71 of file configuration_files.hpp.

◆ getIncompleteWarnings()

std::vector< std::string > moveit_setup::core::ConfigurationFiles::getIncompleteWarnings ( ) const

Definition at line 112 of file configuration_files.cpp.

◆ getInvalidGroupName()

std::string moveit_setup::core::ConfigurationFiles::getInvalidGroupName ( ) const

Definition at line 157 of file configuration_files.cpp.

◆ getName()

std::string moveit_setup::core::ConfigurationFiles::getName ( ) const
inlineoverridevirtual

Returns the name of the setup step.

Implements moveit_setup::SetupStep.

Definition at line 46 of file configuration_files.hpp.

◆ getNumFiles()

unsigned int moveit_setup::core::ConfigurationFiles::getNumFiles ( ) const
inline

Definition at line 76 of file configuration_files.hpp.

◆ getPackagePath()

const std::filesystem::path & moveit_setup::core::ConfigurationFiles::getPackagePath ( )
inline

Definition at line 53 of file configuration_files.hpp.

Here is the caller graph for this function:

◆ hasConflictingFiles()

bool moveit_setup::core::ConfigurationFiles::hasConflictingFiles ( ) const
inline

Definition at line 97 of file configuration_files.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ hasMatchingFileStatus()

bool moveit_setup::core::ConfigurationFiles::hasMatchingFileStatus ( FileStatus  status) const
protected

Definition at line 79 of file configuration_files.cpp.

Here is the caller graph for this function:

◆ hasModifiedFiles()

bool moveit_setup::core::ConfigurationFiles::hasModifiedFiles ( ) const
inline

Definition at line 92 of file configuration_files.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ hasSetupAssistantFile()

bool moveit_setup::core::ConfigurationFiles::hasSetupAssistantFile ( )

Definition at line 103 of file configuration_files.cpp.

Here is the call graph for this function:

◆ isExistingConfig()

bool moveit_setup::core::ConfigurationFiles::isExistingConfig ( )

Definition at line 96 of file configuration_files.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadFiles()

void moveit_setup::core::ConfigurationFiles::loadFiles ( )

Populate the 'Files to be generated' list.

Definition at line 58 of file configuration_files.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadTemplateVariables()

void moveit_setup::core::ConfigurationFiles::loadTemplateVariables ( )

Definition at line 48 of file configuration_files.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInit()

void moveit_setup::core::ConfigurationFiles::onInit ( )
overridevirtual

Overridable initialization method.

Reimplemented from moveit_setup::SetupStep.

Definition at line 43 of file configuration_files.cpp.

◆ setGenerationTime()

void moveit_setup::core::ConfigurationFiles::setGenerationTime ( )
inline

Definition at line 113 of file configuration_files.hpp.

◆ setPackageName()

void moveit_setup::core::ConfigurationFiles::setPackageName ( const std::string &  package_name)
inline

Definition at line 63 of file configuration_files.hpp.

◆ setPackagePath()

void moveit_setup::core::ConfigurationFiles::setPackagePath ( const std::filesystem::path &  package_path)
inline

Definition at line 58 of file configuration_files.hpp.

◆ setShouldGenerate()

void moveit_setup::core::ConfigurationFiles::setShouldGenerate ( const std::string &  rel_path,
bool  should_generate 
)

Definition at line 91 of file configuration_files.cpp.

◆ shouldGenerate()

bool moveit_setup::core::ConfigurationFiles::shouldGenerate ( const GeneratedFilePtr &  file) const
inline

Definition at line 81 of file configuration_files.hpp.

Member Data Documentation

◆ gen_files_

std::vector<GeneratedFilePtr> moveit_setup::core::ConfigurationFiles::gen_files_
protected

Vector of all files to be generated.

Definition at line 125 of file configuration_files.hpp.

◆ package_settings_

std::shared_ptr<PackageSettingsConfig> moveit_setup::core::ConfigurationFiles::package_settings_
protected

Definition at line 129 of file configuration_files.hpp.

◆ should_generate_

std::unordered_map<std::string, bool> moveit_setup::core::ConfigurationFiles::should_generate_
protected

Definition at line 127 of file configuration_files.hpp.


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