|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Stores which LaunchBundles are configured to be generated. More...
#include <launches_config.hpp>


Public Member Functions | |
| bool | isConfigured () const override |
| Return true if this part of the configuration is completely set up. | |
| bool | isIncluded (const LaunchBundle &bundle) const |
| void | include (const LaunchBundle &bundle) |
| Add the given launch bundle to the set. | |
| void | remove (const LaunchBundle &bundle) |
| Remove the given launch bundle from the set. | |
| void | collectDependencies (std::set< std::string > &packages) const override |
| Add the dependencies from the launch bundles to the moveit config's dependencies. | |
| void | collectFiles (const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, std::vector< GeneratedFilePtr > &files) override |
| Provide the files to be generated. | |
Public Member Functions inherited from moveit_setup::SetupConfig | |
| SetupConfig ()=default | |
| SetupConfig (const SetupConfig &)=default | |
| SetupConfig (SetupConfig &&)=default | |
| SetupConfig & | operator= (const SetupConfig &)=default |
| SetupConfig & | operator= (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. | |
| virtual void | onInit () |
| Overridable initialization method. | |
| const std::string & | getName () |
| The name for this part of the configuration. | |
| virtual void | loadPrevious (const std::filesystem::path &, const YAML::Node &) |
| Loads the configuration from an existing MoveIt configuration. | |
| virtual YAML::Node | saveToYaml () const |
| Optionally save "meta" information for saving in the .setup_assistant yaml file. | |
| virtual void | collectVariables (std::vector< TemplateVariable > &) |
| Collect key/value pairs for use in templates. | |
Protected Attributes | |
| std::set< LaunchBundle > | bundles_ |
Protected Attributes inherited from moveit_setup::SetupConfig | |
| std::shared_ptr< DataWarehouse > | config_data_ |
| rclcpp::Node::SharedPtr | parent_node_ |
| std::string | name_ |
| std::shared_ptr< rclcpp::Logger > | logger_ |
Stores which LaunchBundles are configured to be generated.
Saved as a set in which the bundles to be generated are included in the set.
Definition at line 52 of file launches_config.hpp.
|
overridevirtual |
Add the dependencies from the launch bundles to the moveit config's dependencies.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 58 of file launches_config.cpp.
|
overridevirtual |
Provide the files to be generated.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 70 of file launches_config.cpp.
| void moveit_setup::app::LaunchesConfig::include | ( | const LaunchBundle & | bundle | ) |
Add the given launch bundle to the set.
Definition at line 48 of file launches_config.cpp.

|
inlineoverridevirtual |
Return true if this part of the configuration is completely set up.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 55 of file launches_config.hpp.
| bool moveit_setup::app::LaunchesConfig::isIncluded | ( | const LaunchBundle & | bundle | ) | const |
Definition at line 43 of file launches_config.cpp.
| void moveit_setup::app::LaunchesConfig::remove | ( | const LaunchBundle & | bundle | ) |
Remove the given launch bundle from the set.
Definition at line 53 of file launches_config.cpp.
|
protected |
Definition at line 87 of file launches_config.hpp.