moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Attributes | List of all members
moveit_simple_controller_manager::MoveItSimpleControllerManager Class Reference
Inheritance diagram for moveit_simple_controller_manager::MoveItSimpleControllerManager:
Inheritance graph
[legend]
Collaboration diagram for moveit_simple_controller_manager::MoveItSimpleControllerManager:
Collaboration graph
[legend]

Public Member Functions

 MoveItSimpleControllerManager ()=default
 
 ~MoveItSimpleControllerManager () override=default
 
void initialize (const rclcpp::Node::SharedPtr &node) override
 
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle (const std::string &name) override
 Return a given named controller. More...
 
void getControllersList (std::vector< std::string > &names) override
 Get the list of known controller names. More...
 
void getActiveControllers (std::vector< std::string > &names) override
 Get the list of active controllers. More...
 
virtual void getLoadedControllers (std::vector< std::string > &names)
 
void getControllerJoints (const std::string &name, std::vector< std::string > &joints) override
 Report the joints a controller operates on, given the controller name. More...
 
moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState (const std::string &name) override
 Report the state of a controller, given its name. More...
 
bool switchControllers (const std::vector< std::string > &, const std::vector< std::string > &) override
 Activate and deactivate controllers. More...
 
- Public Member Functions inherited from moveit_controller_manager::MoveItControllerManager
 MoveItControllerManager ()
 Default constructor. This needs to have no arguments so that the plugin system can construct the object. More...
 
virtual ~MoveItControllerManager ()
 

Protected Attributes

rclcpp::Node::SharedPtr node_
 
std::map< std::string, ActionBasedControllerHandleBasePtr > controllers_
 
std::map< std::string, moveit_controller_manager::MoveItControllerManager::ControllerStatecontroller_states_
 

Detailed Description

Definition at line 94 of file moveit_simple_controller_manager.cpp.

Constructor & Destructor Documentation

◆ MoveItSimpleControllerManager()

moveit_simple_controller_manager::MoveItSimpleControllerManager::MoveItSimpleControllerManager ( )
default

◆ ~MoveItSimpleControllerManager()

moveit_simple_controller_manager::MoveItSimpleControllerManager::~MoveItSimpleControllerManager ( )
overridedefault

Member Function Documentation

◆ getActiveControllers()

void moveit_simple_controller_manager::MoveItSimpleControllerManager::getActiveControllers ( std::vector< std::string > &  names)
inlineoverridevirtual

Get the list of active controllers.

If there is only one controller in the system, this will be active. When multiple controllers exist, and they operate on overlapping sets of joints, not all controllers should be active at the same time.

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 251 of file moveit_simple_controller_manager.cpp.

Here is the call graph for this function:

◆ getControllerHandle()

moveit_controller_manager::MoveItControllerHandlePtr moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllerHandle ( const std::string &  name)
inlineoverridevirtual

Return a given named controller.

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 222 of file moveit_simple_controller_manager.cpp.

Here is the call graph for this function:

◆ getControllerJoints()

void moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllerJoints ( const std::string &  name,
std::vector< std::string > &  joints 
)
inlineoverridevirtual

Report the joints a controller operates on, given the controller name.

In order to decide which controller to use, it is necessary to reason about the joints a controller operates on.

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 267 of file moveit_simple_controller_manager.cpp.

Here is the call graph for this function:

◆ getControllersList()

void moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllersList ( std::vector< std::string > &  names)
inlineoverridevirtual

Get the list of known controller names.

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 239 of file moveit_simple_controller_manager.cpp.

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

◆ getControllerState()

moveit_controller_manager::MoveItControllerManager::ControllerState moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllerState ( const std::string &  name)
inlineoverridevirtual

Report the state of a controller, given its name.

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 285 of file moveit_simple_controller_manager.cpp.

◆ getLoadedControllers()

virtual void moveit_simple_controller_manager::MoveItSimpleControllerManager::getLoadedControllers ( std::vector< std::string > &  names)
inlinevirtual

Definition at line 259 of file moveit_simple_controller_manager.cpp.

Here is the call graph for this function:

◆ initialize()

void moveit_simple_controller_manager::MoveItSimpleControllerManager::initialize ( const rclcpp::Node::SharedPtr &  node)
inlineoverridevirtual

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 101 of file moveit_simple_controller_manager.cpp.

Here is the call graph for this function:

◆ switchControllers()

bool moveit_simple_controller_manager::MoveItSimpleControllerManager::switchControllers ( const std::vector< std::string > &  activate,
const std::vector< std::string > &  deactivate 
)
inlineoverridevirtual

Activate and deactivate controllers.

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 291 of file moveit_simple_controller_manager.cpp.

Member Data Documentation

◆ controller_states_

std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState> moveit_simple_controller_manager::MoveItSimpleControllerManager::controller_states_
protected

Definition at line 300 of file moveit_simple_controller_manager.cpp.

◆ controllers_

std::map<std::string, ActionBasedControllerHandleBasePtr> moveit_simple_controller_manager::MoveItSimpleControllerManager::controllers_
protected

Definition at line 299 of file moveit_simple_controller_manager.cpp.

◆ node_

rclcpp::Node::SharedPtr moveit_simple_controller_manager::MoveItSimpleControllerManager::node_
protected

Definition at line 298 of file moveit_simple_controller_manager.cpp.


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