| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
#include <moveit_controllers.hpp>


Classes | |
| class | ActionNamespaceField | 
| class | DefaultField | 
Public Member Functions | |
| std::string | getName () const override | 
| Returns the name of the setup step.  More... | |
| void | onInit () override | 
| Overridable initialization method.  More... | |
| std::string | getInstructions () const override | 
| std::string | getButtonText () const override | 
| std::vector< std::string > | getAvailableTypes () const override | 
| std::string | getDefaultType () const override | 
| FieldPointers | getAdditionalControllerFields () const override | 
| Define the types of controller fields for the specific types of controllers.  More... | |
  Public Member Functions inherited from moveit_setup::controllers::Controllers | |
| bool | isReady () const override | 
| Return true if the data necessary to proceed with this step has been configured.  More... | |
| const std::vector< std::string > & | getJointNames () const | 
| std::vector< std::string > | getGroupNames () const | 
| std::string | getChildOfJoint (const std::string &joint_name) const | 
| std::vector< ControllerInfo > & | getControllers () const | 
| bool | addController (const ControllerInfo &new_controller) | 
| ControllerInfo * | findControllerByName (const std::string &controller_name) | 
| bool | deleteController (const std::string &controller_name) | 
| bool | addDefaultControllers () | 
| std::vector< std::string > | getJointsFromGroups (const std::vector< std::string > &group_names) const | 
  Public Member Functions inherited from moveit_setup::SetupStep | |
| SetupStep ()=default | |
| SetupStep (const SetupStep &)=default | |
| SetupStep (SetupStep &&)=default | |
| SetupStep & | operator= (const SetupStep &)=default | 
| SetupStep & | operator= (SetupStep &&)=default | 
| virtual | ~SetupStep ()=default | 
| void | initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data) | 
| Called after construction to initialize the step.  More... | |
| const rclcpp::Logger & | getLogger () const | 
| Makes a namespaced logger for this step available to the widget.  More... | |
Additional Inherited Members | |
  Protected Attributes inherited from moveit_setup::controllers::Controllers | |
| std::shared_ptr< SRDFConfig > | srdf_config_ | 
| std::shared_ptr< ControllersConfig > | controllers_config_ | 
  Protected Attributes inherited from moveit_setup::SetupStep | |
| DataWarehousePtr | config_data_ | 
| rclcpp::Node::SharedPtr | parent_node_ | 
| std::shared_ptr< rclcpp::Logger > | logger_ | 
Definition at line 46 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Define the types of controller fields for the specific types of controllers.
Reimplemented from moveit_setup::controllers::Controllers.
Definition at line 117 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Implements moveit_setup::controllers::Controllers.
Definition at line 72 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Implements moveit_setup::controllers::Controllers.
Definition at line 67 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Implements moveit_setup::controllers::Controllers.
Definition at line 77 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Implements moveit_setup::controllers::Controllers.
Definition at line 61 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Returns the name of the setup step.
Implements moveit_setup::SetupStep.
Definition at line 49 of file moveit_controllers.hpp.
      
  | 
  inlineoverridevirtual | 
Overridable initialization method.
Reimplemented from moveit_setup::SetupStep.
Definition at line 54 of file moveit_controllers.hpp.