moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <ros2_controllers_config.hpp>
Classes | |
class | GeneratedControllersConfig |
Public Member Functions | |
void | onInit () override |
Overridable initialization method. More... | |
void | loadPrevious (const std::filesystem::path &package_path, const YAML::Node &node) override |
Loads the configuration from an existing MoveIt configuration. More... | |
const ControlInterfaces | getControlInterfaces (const std::vector< std::string > &joint_names) const |
void | collectFiles (const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, std::vector< GeneratedFilePtr > &files) override |
Collect the files generated by this configuration and add them to the vector. More... | |
Public Member Functions inherited from moveit_setup::controllers::ControllersConfig | |
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... | |
ControllerInfo * | findControllerByName (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 | |
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. More... | |
const std::string & | getName () |
The name for this part of the configuration. More... | |
virtual YAML::Node | saveToYaml () const |
Optionally save "meta" information for saving in the .setup_assistant yaml file. 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< ControlXacroConfig > | control_xacro_config_ |
Protected Attributes inherited from moveit_setup::controllers::ControllersConfig | |
std::vector< ControllerInfo > | controllers_ |
Controllers config data. More... | |
bool | changed_ |
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_ |
Definition at line 47 of file ros2_controllers_config.hpp.
|
inlineoverridevirtual |
Collect the files generated by this configuration and add them to the vector.
[in] | package_path | the path to the root of the config package |
[in] | last_gen_time | The time (if any) when the config package was last generated @parma[out] files Where to put the new generated files |
Reimplemented from moveit_setup::SetupConfig.
Definition at line 85 of file ros2_controllers_config.hpp.
const ControlInterfaces moveit_setup::controllers::ROS2ControllersConfig::getControlInterfaces | ( | const std::vector< std::string > & | joint_names | ) | const |
Definition at line 130 of file ros2_controllers_config.cpp.
|
overridevirtual |
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.
package_path | The path to the root folder of the configuration. |
Reimplemented from moveit_setup::SetupConfig.
Definition at line 48 of file ros2_controllers_config.cpp.
|
overridevirtual |
Overridable initialization method.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 43 of file ros2_controllers_config.cpp.
|
protected |
Definition at line 92 of file ros2_controllers_config.hpp.