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

All the controller configurations. More...

#include <controllers_config.hpp>

Inheritance diagram for moveit_setup::controllers::ControllersConfig:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::controllers::ControllersConfig:
Collaboration graph
[legend]

Public Member Functions

bool isConfigured () const override
 Return true if this part of the configuration is completely set up. More...
 
std::vector< ControllerInfo > & getControllers ()
 Gets controllers_ vector. More...
 
bool addController (const std::string &name, const std::string &type, const std::vector< std::string > &joint_names)
 Adds a controller to controllers_ vector. More...
 
bool addController (const ControllerInfo &new_controller)
 Adds a controller to controllers_ vector. More...
 
ControllerInfofindControllerByName (const std::string &controller_name)
 
bool deleteController (const std::string &controller_name)
 
bool hasChangedGroups () const
 
- Public Member Functions inherited from moveit_setup::SetupConfig
 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 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::vector< ControllerInfocontrollers_
 Controllers config data. More...
 
bool changed_
 
- Protected Attributes inherited from moveit_setup::SetupConfig
std::shared_ptr< DataWarehouseconfig_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::string name_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

All the controller configurations.

Definition at line 62 of file controllers_config.hpp.

Member Function Documentation

◆ addController() [1/2]

bool moveit_setup::controllers::ControllersConfig::addController ( const ControllerInfo new_controller)

Adds a controller to controllers_ vector.

Parameters
new_controllera new Controller to add
Returns
true if inserted correctly

Definition at line 55 of file controllers_config.cpp.

Here is the call graph for this function:

◆ addController() [2/2]

bool moveit_setup::controllers::ControllersConfig::addController ( const std::string &  name,
const std::string &  type,
const std::vector< std::string > &  joint_names 
)

Adds a controller to controllers_ vector.

Parameters
nameName of the controller
typetype of the controller
joint_namesvector of the joint names
Returns
true if inserted correctly

Definition at line 45 of file controllers_config.cpp.

◆ deleteController()

bool moveit_setup::controllers::ControllersConfig::deleteController ( const std::string &  controller_name)

Delete controller by name

Parameters
controller_name- name of controller to delete
Returns
true if deleted, false if not found

Definition at line 87 of file controllers_config.cpp.

◆ findControllerByName()

ControllerInfo * moveit_setup::controllers::ControllersConfig::findControllerByName ( const std::string &  controller_name)

Find the associated controller by name

Parameters
controller_name- name of controller to find in datastructure
Returns
pointer to data in datastructure

Definition at line 70 of file controllers_config.cpp.

Here is the caller graph for this function:

◆ getControllers()

std::vector<ControllerInfo>& moveit_setup::controllers::ControllersConfig::getControllers ( )
inline

Gets controllers_ vector.

Definition at line 73 of file controllers_config.hpp.

Here is the caller graph for this function:

◆ hasChangedGroups()

bool moveit_setup::controllers::ControllersConfig::hasChangedGroups ( ) const
inline

Definition at line 110 of file controllers_config.hpp.

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

◆ isConfigured()

bool moveit_setup::controllers::ControllersConfig::isConfigured ( ) const
inlineoverridevirtual

Return true if this part of the configuration is completely set up.

Reimplemented from moveit_setup::SetupConfig.

Definition at line 65 of file controllers_config.hpp.

Member Data Documentation

◆ changed_

bool moveit_setup::controllers::ControllersConfig::changed_
protected

Definition at line 119 of file controllers_config.hpp.

◆ controllers_

std::vector<ControllerInfo> moveit_setup::controllers::ControllersConfig::controllers_
protected

Controllers config data.

Definition at line 118 of file controllers_config.hpp.


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